ImuTypes.h 8.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  5. * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
  6. *
  7. * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
  8. * License as published by the Free Software Foundation, either version 3 of the License, or
  9. * (at your option) any later version.
  10. *
  11. * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
  12. * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  13. * GNU General Public License for more details.
  14. *
  15. * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
  16. * If not, see <http://www.gnu.org/licenses/>.
  17. */
  18. #ifndef IMUTYPES_H
  19. #define IMUTYPES_H
  20. #include <vector>
  21. #include <utility>
  22. #include <opencv2/core/core.hpp>
  23. #include <eigen3/Eigen/Core>
  24. #include <eigen3/Eigen/Geometry>
  25. #include <eigen3/Eigen/Dense>
  26. #include <sophus/se3.hpp>
  27. #include <mutex>
  28. #include "SerializationUtils.h"
  29. #include <boost/serialization/serialization.hpp>
  30. #include <boost/serialization/vector.hpp>
  31. namespace ORB_SLAM3
  32. {
  33. namespace IMU
  34. {
  35. const float GRAVITY_VALUE=9.81;
  36. //IMU measurement (gyro, accelerometer and timestamp)
  37. class Point
  38. {
  39. public:
  40. Point(const float &acc_x, const float &acc_y, const float &acc_z,
  41. const float &ang_vel_x, const float &ang_vel_y, const float &ang_vel_z,
  42. const double &timestamp): a(acc_x,acc_y,acc_z), w(ang_vel_x,ang_vel_y,ang_vel_z), t(timestamp){}
  43. Point(const cv::Point3f Acc, const cv::Point3f Gyro, const double &timestamp):
  44. a(Acc.x,Acc.y,Acc.z), w(Gyro.x,Gyro.y,Gyro.z), t(timestamp){}
  45. public:
  46. Eigen::Vector3f a;
  47. Eigen::Vector3f w;
  48. double t;
  49. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  50. };
  51. //IMU biases (gyro and accelerometer)
  52. class Bias
  53. {
  54. friend class boost::serialization::access;
  55. template<class Archive>
  56. void serialize(Archive & ar, const unsigned int version)
  57. {
  58. ar & bax;
  59. ar & bay;
  60. ar & baz;
  61. ar & bwx;
  62. ar & bwy;
  63. ar & bwz;
  64. }
  65. public:
  66. Bias():bax(0),bay(0),baz(0),bwx(0),bwy(0),bwz(0){}
  67. Bias(const float &b_acc_x, const float &b_acc_y, const float &b_acc_z,
  68. const float &b_ang_vel_x, const float &b_ang_vel_y, const float &b_ang_vel_z):
  69. bax(b_acc_x), bay(b_acc_y), baz(b_acc_z), bwx(b_ang_vel_x), bwy(b_ang_vel_y), bwz(b_ang_vel_z){}
  70. void CopyFrom(Bias &b);
  71. friend std::ostream& operator<< (std::ostream &out, const Bias &b);
  72. public:
  73. float bax, bay, baz;
  74. float bwx, bwy, bwz;
  75. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  76. };
  77. //IMU calibration (Tbc, Tcb, noise)
  78. class Calib
  79. {
  80. friend class boost::serialization::access;
  81. template<class Archive>
  82. void serialize(Archive & ar, const unsigned int version)
  83. {
  84. serializeSophusSE3(ar,mTcb,version);
  85. serializeSophusSE3(ar,mTbc,version);
  86. ar & boost::serialization::make_array(Cov.diagonal().data(), Cov.diagonal().size());
  87. ar & boost::serialization::make_array(CovWalk.diagonal().data(), CovWalk.diagonal().size());
  88. ar & mbIsSet;
  89. }
  90. public:
  91. Calib(const Sophus::SE3<float> &Tbc, const float &ng, const float &na, const float &ngw, const float &naw)
  92. {
  93. Set(Tbc,ng,na,ngw,naw);
  94. }
  95. Calib(const Calib &calib);
  96. Calib(){mbIsSet = false;}
  97. //void Set(const cv::Mat &cvTbc, const float &ng, const float &na, const float &ngw, const float &naw);
  98. void Set(const Sophus::SE3<float> &sophTbc, const float &ng, const float &na, const float &ngw, const float &naw);
  99. public:
  100. // Sophus/Eigen implementation
  101. Sophus::SE3<float> mTcb;
  102. Sophus::SE3<float> mTbc;
  103. Eigen::DiagonalMatrix<float,6> Cov, CovWalk;
  104. bool mbIsSet;
  105. };
  106. //Integration of 1 gyro measurement
  107. class IntegratedRotation
  108. {
  109. public:
  110. IntegratedRotation(){}
  111. IntegratedRotation(const Eigen::Vector3f &angVel, const Bias &imuBias, const float &time);
  112. public:
  113. float deltaT; //integration time
  114. Eigen::Matrix3f deltaR;
  115. Eigen::Matrix3f rightJ; // right jacobian
  116. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  117. };
  118. //Preintegration of Imu Measurements
  119. class Preintegrated
  120. {
  121. friend class boost::serialization::access;
  122. template<class Archive>
  123. void serialize(Archive & ar, const unsigned int version)
  124. {
  125. ar & dT;
  126. ar & boost::serialization::make_array(C.data(), C.size());
  127. ar & boost::serialization::make_array(Info.data(), Info.size());
  128. ar & boost::serialization::make_array(Nga.diagonal().data(), Nga.diagonal().size());
  129. ar & boost::serialization::make_array(NgaWalk.diagonal().data(), NgaWalk.diagonal().size());
  130. ar & b;
  131. ar & boost::serialization::make_array(dR.data(), dR.size());
  132. ar & boost::serialization::make_array(dV.data(), dV.size());
  133. ar & boost::serialization::make_array(dP.data(), dP.size());
  134. ar & boost::serialization::make_array(JRg.data(), JRg.size());
  135. ar & boost::serialization::make_array(JVg.data(), JVg.size());
  136. ar & boost::serialization::make_array(JVa.data(), JVa.size());
  137. ar & boost::serialization::make_array(JPg.data(), JPg.size());
  138. ar & boost::serialization::make_array(JPa.data(), JPa.size());
  139. ar & boost::serialization::make_array(avgA.data(), avgA.size());
  140. ar & boost::serialization::make_array(avgW.data(), avgW.size());
  141. ar & bu;
  142. ar & boost::serialization::make_array(db.data(), db.size());
  143. ar & mvMeasurements;
  144. }
  145. public:
  146. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  147. Preintegrated(const Bias &b_, const Calib &calib);
  148. Preintegrated(Preintegrated* pImuPre);
  149. Preintegrated() {}
  150. ~Preintegrated() {}
  151. void CopyFrom(Preintegrated* pImuPre);
  152. void Initialize(const Bias &b_);
  153. void IntegrateNewMeasurement(const Eigen::Vector3f &acceleration, const Eigen::Vector3f &angVel, const float &dt);
  154. void Reintegrate();
  155. void MergePrevious(Preintegrated* pPrev);
  156. void SetNewBias(const Bias &bu_);
  157. IMU::Bias GetDeltaBias(const Bias &b_);
  158. Eigen::Matrix3f GetDeltaRotation(const Bias &b_);
  159. Eigen::Vector3f GetDeltaVelocity(const Bias &b_);
  160. Eigen::Vector3f GetDeltaPosition(const Bias &b_);
  161. Eigen::Matrix3f GetUpdatedDeltaRotation();
  162. Eigen::Vector3f GetUpdatedDeltaVelocity();
  163. Eigen::Vector3f GetUpdatedDeltaPosition();
  164. Eigen::Matrix3f GetOriginalDeltaRotation();
  165. Eigen::Vector3f GetOriginalDeltaVelocity();
  166. Eigen::Vector3f GetOriginalDeltaPosition();
  167. Eigen::Matrix<float,6,1> GetDeltaBias();
  168. Bias GetOriginalBias();
  169. Bias GetUpdatedBias();
  170. void printMeasurements() const {
  171. std::cout << "pint meas:\n";
  172. for(int i=0; i<mvMeasurements.size(); i++){
  173. std::cout << "meas " << mvMeasurements[i].t << std::endl;
  174. }
  175. std::cout << "end pint meas:\n";
  176. }
  177. public:
  178. float dT;
  179. Eigen::Matrix<float,15,15> C;
  180. Eigen::Matrix<float,15,15> Info;
  181. Eigen::DiagonalMatrix<float,6> Nga, NgaWalk;
  182. // Values for the original bias (when integration was computed)
  183. Bias b;
  184. Eigen::Matrix3f dR;
  185. Eigen::Vector3f dV, dP;
  186. Eigen::Matrix3f JRg, JVg, JVa, JPg, JPa;
  187. Eigen::Vector3f avgA, avgW;
  188. private:
  189. // Updated bias
  190. Bias bu;
  191. // Dif between original and updated bias
  192. // This is used to compute the updated values of the preintegration
  193. Eigen::Matrix<float,6,1> db;
  194. struct integrable
  195. {
  196. template<class Archive>
  197. void serialize(Archive & ar, const unsigned int version)
  198. {
  199. ar & boost::serialization::make_array(a.data(), a.size());
  200. ar & boost::serialization::make_array(w.data(), w.size());
  201. ar & t;
  202. }
  203. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  204. integrable(){}
  205. integrable(const Eigen::Vector3f &a_, const Eigen::Vector3f &w_ , const float &t_):a(a_),w(w_),t(t_){}
  206. Eigen::Vector3f a, w;
  207. float t;
  208. };
  209. std::vector<integrable> mvMeasurements;
  210. std::mutex mMutex;
  211. };
  212. // Lie Algebra Functions
  213. Eigen::Matrix3f RightJacobianSO3(const float &x, const float &y, const float &z);
  214. Eigen::Matrix3f RightJacobianSO3(const Eigen::Vector3f &v);
  215. Eigen::Matrix3f InverseRightJacobianSO3(const float &x, const float &y, const float &z);
  216. Eigen::Matrix3f InverseRightJacobianSO3(const Eigen::Vector3f &v);
  217. Eigen::Matrix3f NormalizeRotation(const Eigen::Matrix3f &R);
  218. }
  219. } //namespace ORB_SLAM2
  220. #endif // IMUTYPES_H