ImuTypes.h 8.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285
  1. /**
  2. * This file is part of ORB-SLAM3
  3. *
  4. * Copyright (C) 2017-2020 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 <Eigen/Core>
  24. #include <Eigen/Geometry>
  25. #include <Eigen/Dense>
  26. #include <mutex>
  27. #include <boost/serialization/serialization.hpp>
  28. #include <boost/serialization/vector.hpp>
  29. namespace ORB_SLAM3
  30. {
  31. namespace IMU
  32. {
  33. const float GRAVITY_VALUE=9.81;
  34. //IMU measurement (gyro, accelerometer and timestamp)
  35. class Point
  36. {
  37. public:
  38. Point(const float &acc_x, const float &acc_y, const float &acc_z,
  39. const float &ang_vel_x, const float &ang_vel_y, const float &ang_vel_z,
  40. const double &timestamp): a(acc_x,acc_y,acc_z), w(ang_vel_x,ang_vel_y,ang_vel_z), t(timestamp){}
  41. Point(const cv::Point3f Acc, const cv::Point3f Gyro, const double &timestamp):
  42. a(Acc.x,Acc.y,Acc.z), w(Gyro.x,Gyro.y,Gyro.z), t(timestamp){}
  43. public:
  44. cv::Point3f a;
  45. cv::Point3f w;
  46. double t;
  47. };
  48. //IMU biases (gyro and accelerometer)
  49. class Bias
  50. {
  51. friend class boost::serialization::access;
  52. template<class Archive>
  53. void serialize(Archive & ar, const unsigned int version)
  54. {
  55. ar & bax;
  56. ar & bay;
  57. ar & baz;
  58. ar & bwx;
  59. ar & bwy;
  60. ar & bwz;
  61. }
  62. public:
  63. Bias():bax(0),bay(0),baz(0),bwx(0),bwy(0),bwz(0){}
  64. Bias(const float &b_acc_x, const float &b_acc_y, const float &b_acc_z,
  65. const float &b_ang_vel_x, const float &b_ang_vel_y, const float &b_ang_vel_z):
  66. 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){}
  67. void CopyFrom(Bias &b);
  68. friend std::ostream& operator<< (std::ostream &out, const Bias &b);
  69. public:
  70. float bax, bay, baz;
  71. float bwx, bwy, bwz;
  72. };
  73. //IMU calibration (Tbc, Tcb, noise)
  74. class Calib
  75. {
  76. template<class Archive>
  77. void serializeMatrix(Archive &ar, cv::Mat& mat, const unsigned int version)
  78. {
  79. int cols, rows, type;
  80. bool continuous;
  81. if (Archive::is_saving::value) {
  82. cols = mat.cols; rows = mat.rows; type = mat.type();
  83. continuous = mat.isContinuous();
  84. }
  85. ar & cols & rows & type & continuous;
  86. if (Archive::is_loading::value)
  87. mat.create(rows, cols, type);
  88. if (continuous) {
  89. const unsigned int data_size = rows * cols * mat.elemSize();
  90. ar & boost::serialization::make_array(mat.ptr(), data_size);
  91. } else {
  92. const unsigned int row_size = cols*mat.elemSize();
  93. for (int i = 0; i < rows; i++) {
  94. ar & boost::serialization::make_array(mat.ptr(i), row_size);
  95. }
  96. }
  97. }
  98. friend class boost::serialization::access;
  99. template<class Archive>
  100. void serialize(Archive & ar, const unsigned int version)
  101. {
  102. serializeMatrix(ar,Tcb,version);
  103. serializeMatrix(ar,Tbc,version);
  104. serializeMatrix(ar,Cov,version);
  105. serializeMatrix(ar,CovWalk,version);
  106. }
  107. public:
  108. Calib(const cv::Mat &Tbc_, const float &ng, const float &na, const float &ngw, const float &naw)
  109. {
  110. Set(Tbc_,ng,na,ngw,naw);
  111. }
  112. Calib(const Calib &calib);
  113. Calib(){}
  114. void Set(const cv::Mat &Tbc_, const float &ng, const float &na, const float &ngw, const float &naw);
  115. public:
  116. cv::Mat Tcb;
  117. cv::Mat Tbc;
  118. cv::Mat Cov, CovWalk;
  119. };
  120. //Integration of 1 gyro measurement
  121. class IntegratedRotation
  122. {
  123. public:
  124. IntegratedRotation(){}
  125. IntegratedRotation(const cv::Point3f &angVel, const Bias &imuBias, const float &time);
  126. public:
  127. float deltaT; //integration time
  128. cv::Mat deltaR; //integrated rotation
  129. cv::Mat rightJ; // right jacobian
  130. };
  131. //Preintegration of Imu Measurements
  132. class Preintegrated
  133. {
  134. template<class Archive>
  135. void serializeMatrix(Archive &ar, cv::Mat& mat, const unsigned int version)
  136. {
  137. int cols, rows, type;
  138. bool continuous;
  139. if (Archive::is_saving::value) {
  140. cols = mat.cols; rows = mat.rows; type = mat.type();
  141. continuous = mat.isContinuous();
  142. }
  143. ar & cols & rows & type & continuous;
  144. if (Archive::is_loading::value)
  145. mat.create(rows, cols, type);
  146. if (continuous) {
  147. const unsigned int data_size = rows * cols * mat.elemSize();
  148. ar & boost::serialization::make_array(mat.ptr(), data_size);
  149. } else {
  150. const unsigned int row_size = cols*mat.elemSize();
  151. for (int i = 0; i < rows; i++) {
  152. ar & boost::serialization::make_array(mat.ptr(i), row_size);
  153. }
  154. }
  155. }
  156. friend class boost::serialization::access;
  157. template<class Archive>
  158. void serialize(Archive & ar, const unsigned int version)
  159. {
  160. ar & dT;
  161. serializeMatrix(ar,C,version);
  162. serializeMatrix(ar,Info,version);
  163. serializeMatrix(ar,Nga,version);
  164. serializeMatrix(ar,NgaWalk,version);
  165. ar & b;
  166. serializeMatrix(ar,dR,version);
  167. serializeMatrix(ar,dV,version);
  168. serializeMatrix(ar,dP,version);
  169. serializeMatrix(ar,JRg,version);
  170. serializeMatrix(ar,JVg,version);
  171. serializeMatrix(ar,JVa,version);
  172. serializeMatrix(ar,JPg,version);
  173. serializeMatrix(ar,JPa,version);
  174. serializeMatrix(ar,avgA,version);
  175. serializeMatrix(ar,avgW,version);
  176. ar & bu;
  177. serializeMatrix(ar,db,version);
  178. ar & mvMeasurements;
  179. }
  180. public:
  181. Preintegrated(const Bias &b_, const Calib &calib);
  182. Preintegrated(Preintegrated* pImuPre);
  183. Preintegrated() {}
  184. ~Preintegrated() {}
  185. void CopyFrom(Preintegrated* pImuPre);
  186. void Initialize(const Bias &b_);
  187. void IntegrateNewMeasurement(const cv::Point3f &acceleration, const cv::Point3f &angVel, const float &dt);
  188. void Reintegrate();
  189. void MergePrevious(Preintegrated* pPrev);
  190. void SetNewBias(const Bias &bu_);
  191. IMU::Bias GetDeltaBias(const Bias &b_);
  192. cv::Mat GetDeltaRotation(const Bias &b_);
  193. cv::Mat GetDeltaVelocity(const Bias &b_);
  194. cv::Mat GetDeltaPosition(const Bias &b_);
  195. cv::Mat GetUpdatedDeltaRotation();
  196. cv::Mat GetUpdatedDeltaVelocity();
  197. cv::Mat GetUpdatedDeltaPosition();
  198. cv::Mat GetOriginalDeltaRotation();
  199. cv::Mat GetOriginalDeltaVelocity();
  200. cv::Mat GetOriginalDeltaPosition();
  201. Eigen::Matrix<double,15,15> GetInformationMatrix();
  202. cv::Mat GetDeltaBias();
  203. Bias GetOriginalBias();
  204. Bias GetUpdatedBias();
  205. public:
  206. float dT;
  207. cv::Mat C;
  208. cv::Mat Info;
  209. cv::Mat Nga, NgaWalk;
  210. // Values for the original bias (when integration was computed)
  211. Bias b;
  212. cv::Mat dR, dV, dP;
  213. cv::Mat JRg, JVg, JVa, JPg, JPa;
  214. cv::Mat avgA;
  215. cv::Mat avgW;
  216. private:
  217. // Updated bias
  218. Bias bu;
  219. // Dif between original and updated bias
  220. // This is used to compute the updated values of the preintegration
  221. cv::Mat db;
  222. struct integrable
  223. {
  224. integrable(const cv::Point3f &a_, const cv::Point3f &w_ , const float &t_):a(a_),w(w_),t(t_){}
  225. cv::Point3f a;
  226. cv::Point3f w;
  227. float t;
  228. };
  229. std::vector<integrable> mvMeasurements;
  230. std::mutex mMutex;
  231. };
  232. // Lie Algebra Functions
  233. cv::Mat ExpSO3(const float &x, const float &y, const float &z);
  234. Eigen::Matrix<double,3,3> ExpSO3(const double &x, const double &y, const double &z);
  235. cv::Mat ExpSO3(const cv::Mat &v);
  236. cv::Mat LogSO3(const cv::Mat &R);
  237. cv::Mat RightJacobianSO3(const float &x, const float &y, const float &z);
  238. cv::Mat RightJacobianSO3(const cv::Mat &v);
  239. cv::Mat InverseRightJacobianSO3(const float &x, const float &y, const float &z);
  240. cv::Mat InverseRightJacobianSO3(const cv::Mat &v);
  241. cv::Mat Skew(const cv::Mat &v);
  242. cv::Mat NormalizeRotation(const cv::Mat &R);
  243. }
  244. } //namespace ORB_SLAM2
  245. #endif // IMUTYPES_H