ImuTypes.cc 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421
  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. #include "ImuTypes.h"
  19. #include "Converter.h"
  20. #include "GeometricTools.h"
  21. #include<iostream>
  22. namespace ORB_SLAM3
  23. {
  24. namespace IMU
  25. {
  26. const float eps = 1e-4;
  27. Eigen::Matrix3f NormalizeRotation(const Eigen::Matrix3f &R){
  28. Eigen::JacobiSVD<Eigen::Matrix3f> svd(R, Eigen::ComputeFullU | Eigen::ComputeFullV);
  29. return svd.matrixU() * svd.matrixV().transpose();
  30. }
  31. Eigen::Matrix3f RightJacobianSO3(const float &x, const float &y, const float &z)
  32. {
  33. Eigen::Matrix3f I;
  34. I.setIdentity();
  35. const float d2 = x*x+y*y+z*z;
  36. const float d = sqrt(d2);
  37. Eigen::Vector3f v;
  38. v << x, y, z;
  39. Eigen::Matrix3f W = Sophus::SO3f::hat(v);
  40. if(d<eps) {
  41. return I;
  42. }
  43. else {
  44. return I - W*(1.0f-cos(d))/d2 + W*W*(d-sin(d))/(d2*d);
  45. }
  46. }
  47. Eigen::Matrix3f RightJacobianSO3(const Eigen::Vector3f &v)
  48. {
  49. return RightJacobianSO3(v(0),v(1),v(2));
  50. }
  51. Eigen::Matrix3f InverseRightJacobianSO3(const float &x, const float &y, const float &z)
  52. {
  53. Eigen::Matrix3f I;
  54. I.setIdentity();
  55. const float d2 = x*x+y*y+z*z;
  56. const float d = sqrt(d2);
  57. Eigen::Vector3f v;
  58. v << x, y, z;
  59. Eigen::Matrix3f W = Sophus::SO3f::hat(v);
  60. if(d<eps) {
  61. return I;
  62. }
  63. else {
  64. return I + W/2 + W*W*(1.0f/d2 - (1.0f+cos(d))/(2.0f*d*sin(d)));
  65. }
  66. }
  67. Eigen::Matrix3f InverseRightJacobianSO3(const Eigen::Vector3f &v)
  68. {
  69. return InverseRightJacobianSO3(v(0),v(1),v(2));
  70. }
  71. IntegratedRotation::IntegratedRotation(const Eigen::Vector3f &angVel, const Bias &imuBias, const float &time) {
  72. const float x = (angVel(0)-imuBias.bwx)*time;
  73. const float y = (angVel(1)-imuBias.bwy)*time;
  74. const float z = (angVel(2)-imuBias.bwz)*time;
  75. const float d2 = x*x+y*y+z*z;
  76. const float d = sqrt(d2);
  77. Eigen::Vector3f v;
  78. v << x, y, z;
  79. Eigen::Matrix3f W = Sophus::SO3f::hat(v);
  80. if(d<eps)
  81. {
  82. deltaR = Eigen::Matrix3f::Identity() + W;
  83. rightJ = Eigen::Matrix3f::Identity();
  84. }
  85. else
  86. {
  87. deltaR = Eigen::Matrix3f::Identity() + W*sin(d)/d + W*W*(1.0f-cos(d))/d2;
  88. rightJ = Eigen::Matrix3f::Identity() - W*(1.0f-cos(d))/d2 + W*W*(d-sin(d))/(d2*d);
  89. }
  90. }
  91. Preintegrated::Preintegrated(const Bias &b_, const Calib &calib)
  92. {
  93. Nga = calib.Cov;
  94. NgaWalk = calib.CovWalk;
  95. Initialize(b_);
  96. }
  97. // Copy constructor
  98. Preintegrated::Preintegrated(Preintegrated* pImuPre): dT(pImuPre->dT),C(pImuPre->C), Info(pImuPre->Info),
  99. Nga(pImuPre->Nga), NgaWalk(pImuPre->NgaWalk), b(pImuPre->b), dR(pImuPre->dR), dV(pImuPre->dV),
  100. dP(pImuPre->dP), JRg(pImuPre->JRg), JVg(pImuPre->JVg), JVa(pImuPre->JVa), JPg(pImuPre->JPg), JPa(pImuPre->JPa),
  101. avgA(pImuPre->avgA), avgW(pImuPre->avgW), bu(pImuPre->bu), db(pImuPre->db), mvMeasurements(pImuPre->mvMeasurements)
  102. {
  103. }
  104. void Preintegrated::CopyFrom(Preintegrated* pImuPre)
  105. {
  106. dT = pImuPre->dT;
  107. C = pImuPre->C;
  108. Info = pImuPre->Info;
  109. Nga = pImuPre->Nga;
  110. NgaWalk = pImuPre->NgaWalk;
  111. b.CopyFrom(pImuPre->b);
  112. dR = pImuPre->dR;
  113. dV = pImuPre->dV;
  114. dP = pImuPre->dP;
  115. JRg = pImuPre->JRg;
  116. JVg = pImuPre->JVg;
  117. JVa = pImuPre->JVa;
  118. JPg = pImuPre->JPg;
  119. JPa = pImuPre->JPa;
  120. avgA = pImuPre->avgA;
  121. avgW = pImuPre->avgW;
  122. bu.CopyFrom(pImuPre->bu);
  123. db = pImuPre->db;
  124. mvMeasurements = pImuPre->mvMeasurements;
  125. }
  126. void Preintegrated::Initialize(const Bias &b_)
  127. {
  128. dR.setIdentity();
  129. dV.setZero();
  130. dP.setZero();
  131. JRg.setZero();
  132. JVg.setZero();
  133. JVa.setZero();
  134. JPg.setZero();
  135. JPa.setZero();
  136. C.setZero();
  137. Info.setZero();
  138. db.setZero();
  139. b=b_;
  140. bu=b_;
  141. avgA.setZero();
  142. avgW.setZero();
  143. dT=0.0f;
  144. mvMeasurements.clear();
  145. }
  146. void Preintegrated::Reintegrate()
  147. {
  148. std::unique_lock<std::mutex> lock(mMutex);
  149. const std::vector<integrable> aux = mvMeasurements;
  150. Initialize(bu);
  151. for(size_t i=0;i<aux.size();i++)
  152. IntegrateNewMeasurement(aux[i].a,aux[i].w,aux[i].t);
  153. }
  154. void Preintegrated::IntegrateNewMeasurement(const Eigen::Vector3f &acceleration, const Eigen::Vector3f &angVel, const float &dt)
  155. {
  156. mvMeasurements.push_back(integrable(acceleration,angVel,dt));
  157. // Position is updated firstly, as it depends on previously computed velocity and rotation.
  158. // Velocity is updated secondly, as it depends on previously computed rotation.
  159. // Rotation is the last to be updated.
  160. //Matrices to compute covariance
  161. Eigen::Matrix<float,9,9> A;
  162. A.setIdentity();
  163. Eigen::Matrix<float,9,6> B;
  164. B.setZero();
  165. Eigen::Vector3f acc, accW;
  166. acc << acceleration(0)-b.bax, acceleration(1)-b.bay, acceleration(2)-b.baz;
  167. accW << angVel(0)-b.bwx, angVel(1)-b.bwy, angVel(2)-b.bwz;
  168. avgA = (dT*avgA + dR*acc*dt)/(dT+dt);
  169. avgW = (dT*avgW + accW*dt)/(dT+dt);
  170. // Update delta position dP and velocity dV (rely on no-updated delta rotation)
  171. dP = dP + dV*dt + 0.5f*dR*acc*dt*dt;
  172. dV = dV + dR*acc*dt;
  173. // Compute velocity and position parts of matrices A and B (rely on non-updated delta rotation)
  174. Eigen::Matrix<float,3,3> Wacc = Sophus::SO3f::hat(acc);
  175. A.block<3,3>(3,0) = -dR*dt*Wacc;
  176. A.block<3,3>(6,0) = -0.5f*dR*dt*dt*Wacc;
  177. A.block<3,3>(6,3) = Eigen::DiagonalMatrix<float,3>(dt, dt, dt);
  178. B.block<3,3>(3,3) = dR*dt;
  179. B.block<3,3>(6,3) = 0.5f*dR*dt*dt;
  180. // Update position and velocity jacobians wrt bias correction
  181. JPa = JPa + JVa*dt -0.5f*dR*dt*dt;
  182. JPg = JPg + JVg*dt -0.5f*dR*dt*dt*Wacc*JRg;
  183. JVa = JVa - dR*dt;
  184. JVg = JVg - dR*dt*Wacc*JRg;
  185. // Update delta rotation
  186. IntegratedRotation dRi(angVel,b,dt);
  187. dR = NormalizeRotation(dR*dRi.deltaR);
  188. // Compute rotation parts of matrices A and B
  189. A.block<3,3>(0,0) = dRi.deltaR.transpose();
  190. B.block<3,3>(0,0) = dRi.rightJ*dt;
  191. // Update covariance
  192. C.block<9,9>(0,0) = A * C.block<9,9>(0,0) * A.transpose() + B*Nga*B.transpose();
  193. C.block<6,6>(9,9) += NgaWalk;
  194. // Update rotation jacobian wrt bias correction
  195. JRg = dRi.deltaR.transpose()*JRg - dRi.rightJ*dt;
  196. // Total integrated time
  197. dT += dt;
  198. }
  199. void Preintegrated::MergePrevious(Preintegrated* pPrev)
  200. {
  201. if (pPrev==this)
  202. return;
  203. std::unique_lock<std::mutex> lock1(mMutex);
  204. std::unique_lock<std::mutex> lock2(pPrev->mMutex);
  205. Bias bav;
  206. bav.bwx = bu.bwx;
  207. bav.bwy = bu.bwy;
  208. bav.bwz = bu.bwz;
  209. bav.bax = bu.bax;
  210. bav.bay = bu.bay;
  211. bav.baz = bu.baz;
  212. const std::vector<integrable > aux1 = pPrev->mvMeasurements;
  213. const std::vector<integrable> aux2 = mvMeasurements;
  214. Initialize(bav);
  215. for(size_t i=0;i<aux1.size();i++)
  216. IntegrateNewMeasurement(aux1[i].a,aux1[i].w,aux1[i].t);
  217. for(size_t i=0;i<aux2.size();i++)
  218. IntegrateNewMeasurement(aux2[i].a,aux2[i].w,aux2[i].t);
  219. }
  220. void Preintegrated::SetNewBias(const Bias &bu_)
  221. {
  222. std::unique_lock<std::mutex> lock(mMutex);
  223. bu = bu_;
  224. db(0) = bu_.bwx-b.bwx;
  225. db(1) = bu_.bwy-b.bwy;
  226. db(2) = bu_.bwz-b.bwz;
  227. db(3) = bu_.bax-b.bax;
  228. db(4) = bu_.bay-b.bay;
  229. db(5) = bu_.baz-b.baz;
  230. }
  231. IMU::Bias Preintegrated::GetDeltaBias(const Bias &b_)
  232. {
  233. std::unique_lock<std::mutex> lock(mMutex);
  234. return IMU::Bias(b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz,b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz);
  235. }
  236. Eigen::Matrix3f Preintegrated::GetDeltaRotation(const Bias &b_)
  237. {
  238. std::unique_lock<std::mutex> lock(mMutex);
  239. Eigen::Vector3f dbg;
  240. dbg << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz;
  241. return NormalizeRotation(dR * Sophus::SO3f::exp(JRg * dbg).matrix());
  242. }
  243. Eigen::Vector3f Preintegrated::GetDeltaVelocity(const Bias &b_)
  244. {
  245. std::unique_lock<std::mutex> lock(mMutex);
  246. Eigen::Vector3f dbg, dba;
  247. dbg << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz;
  248. dba << b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz;
  249. return dV + JVg * dbg + JVa * dba;
  250. }
  251. Eigen::Vector3f Preintegrated::GetDeltaPosition(const Bias &b_)
  252. {
  253. std::unique_lock<std::mutex> lock(mMutex);
  254. Eigen::Vector3f dbg, dba;
  255. dbg << b_.bwx-b.bwx,b_.bwy-b.bwy,b_.bwz-b.bwz;
  256. dba << b_.bax-b.bax,b_.bay-b.bay,b_.baz-b.baz;
  257. return dP + JPg * dbg + JPa * dba;
  258. }
  259. Eigen::Matrix3f Preintegrated::GetUpdatedDeltaRotation()
  260. {
  261. std::unique_lock<std::mutex> lock(mMutex);
  262. return NormalizeRotation(dR * Sophus::SO3f::exp(JRg*db.head(3)).matrix());
  263. }
  264. Eigen::Vector3f Preintegrated::GetUpdatedDeltaVelocity()
  265. {
  266. std::unique_lock<std::mutex> lock(mMutex);
  267. return dV + JVg * db.head(3) + JVa * db.tail(3);
  268. }
  269. Eigen::Vector3f Preintegrated::GetUpdatedDeltaPosition()
  270. {
  271. std::unique_lock<std::mutex> lock(mMutex);
  272. return dP + JPg*db.head(3) + JPa*db.tail(3);
  273. }
  274. Eigen::Matrix3f Preintegrated::GetOriginalDeltaRotation() {
  275. std::unique_lock<std::mutex> lock(mMutex);
  276. return dR;
  277. }
  278. Eigen::Vector3f Preintegrated::GetOriginalDeltaVelocity() {
  279. std::unique_lock<std::mutex> lock(mMutex);
  280. return dV;
  281. }
  282. Eigen::Vector3f Preintegrated::GetOriginalDeltaPosition()
  283. {
  284. std::unique_lock<std::mutex> lock(mMutex);
  285. return dP;
  286. }
  287. Bias Preintegrated::GetOriginalBias()
  288. {
  289. std::unique_lock<std::mutex> lock(mMutex);
  290. return b;
  291. }
  292. Bias Preintegrated::GetUpdatedBias()
  293. {
  294. std::unique_lock<std::mutex> lock(mMutex);
  295. return bu;
  296. }
  297. Eigen::Matrix<float,6,1> Preintegrated::GetDeltaBias()
  298. {
  299. std::unique_lock<std::mutex> lock(mMutex);
  300. return db;
  301. }
  302. void Bias::CopyFrom(Bias &b)
  303. {
  304. bax = b.bax;
  305. bay = b.bay;
  306. baz = b.baz;
  307. bwx = b.bwx;
  308. bwy = b.bwy;
  309. bwz = b.bwz;
  310. }
  311. std::ostream& operator<< (std::ostream &out, const Bias &b)
  312. {
  313. if(b.bwx>0)
  314. out << " ";
  315. out << b.bwx << ",";
  316. if(b.bwy>0)
  317. out << " ";
  318. out << b.bwy << ",";
  319. if(b.bwz>0)
  320. out << " ";
  321. out << b.bwz << ",";
  322. if(b.bax>0)
  323. out << " ";
  324. out << b.bax << ",";
  325. if(b.bay>0)
  326. out << " ";
  327. out << b.bay << ",";
  328. if(b.baz>0)
  329. out << " ";
  330. out << b.baz;
  331. return out;
  332. }
  333. void Calib::Set(const Sophus::SE3<float> &sophTbc, const float &ng, const float &na, const float &ngw, const float &naw) {
  334. mbIsSet = true;
  335. const float ng2 = ng*ng;
  336. const float na2 = na*na;
  337. const float ngw2 = ngw*ngw;
  338. const float naw2 = naw*naw;
  339. // Sophus/Eigen
  340. mTbc = sophTbc;
  341. mTcb = mTbc.inverse();
  342. Cov.diagonal() << ng2, ng2, ng2, na2, na2, na2;
  343. CovWalk.diagonal() << ngw2, ngw2, ngw2, naw2, naw2, naw2;
  344. }
  345. Calib::Calib(const Calib &calib)
  346. {
  347. mbIsSet = calib.mbIsSet;
  348. // Sophus/Eigen parameters
  349. mTbc = calib.mTbc;
  350. mTcb = calib.mTcb;
  351. Cov = calib.Cov;
  352. CovWalk = calib.CovWalk;
  353. }
  354. } //namespace IMU
  355. } //namespace ORB_SLAM2