G2oTypes.h 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863
  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 G2OTYPES_H
  19. #define G2OTYPES_H
  20. #include "Thirdparty/g2o/g2o/core/base_vertex.h"
  21. #include "Thirdparty/g2o/g2o/core/base_binary_edge.h"
  22. #include "Thirdparty/g2o/g2o/types/types_sba.h"
  23. #include "Thirdparty/g2o/g2o/core/base_multi_edge.h"
  24. #include "Thirdparty/g2o/g2o/core/base_unary_edge.h"
  25. #include<opencv2/core/core.hpp>
  26. #include <Eigen/Core>
  27. #include <Eigen/Geometry>
  28. #include <Eigen/Dense>
  29. #include <Frame.h>
  30. #include <KeyFrame.h>
  31. #include"Converter.h"
  32. #include <math.h>
  33. namespace ORB_SLAM3
  34. {
  35. class KeyFrame;
  36. class Frame;
  37. class GeometricCamera;
  38. typedef Eigen::Matrix<double, 6, 1> Vector6d;
  39. typedef Eigen::Matrix<double, 9, 1> Vector9d;
  40. typedef Eigen::Matrix<double, 12, 1> Vector12d;
  41. typedef Eigen::Matrix<double, 15, 1> Vector15d;
  42. typedef Eigen::Matrix<double, 12, 12> Matrix12d;
  43. typedef Eigen::Matrix<double, 15, 15> Matrix15d;
  44. typedef Eigen::Matrix<double, 9, 9> Matrix9d;
  45. Eigen::Matrix3d ExpSO3(const double x, const double y, const double z);
  46. Eigen::Matrix3d ExpSO3(const Eigen::Vector3d &w);
  47. Eigen::Vector3d LogSO3(const Eigen::Matrix3d &R);
  48. Eigen::Matrix3d InverseRightJacobianSO3(const Eigen::Vector3d &v);
  49. Eigen::Matrix3d RightJacobianSO3(const Eigen::Vector3d &v);
  50. Eigen::Matrix3d RightJacobianSO3(const double x, const double y, const double z);
  51. Eigen::Matrix3d Skew(const Eigen::Vector3d &w);
  52. Eigen::Matrix3d InverseRightJacobianSO3(const double x, const double y, const double z);
  53. Eigen::Matrix3d NormalizeRotation(const Eigen::Matrix3d &R);
  54. class ImuCamPose
  55. {
  56. public:
  57. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  58. ImuCamPose(){}
  59. ImuCamPose(KeyFrame* pKF);
  60. ImuCamPose(Frame* pF);
  61. ImuCamPose(Eigen::Matrix3d &_Rwc, Eigen::Vector3d &_twc, KeyFrame* pKF);
  62. void SetParam(const std::vector<Eigen::Matrix3d> &_Rcw, const std::vector<Eigen::Vector3d> &_tcw, const std::vector<Eigen::Matrix3d> &_Rbc,
  63. const std::vector<Eigen::Vector3d> &_tbc, const double &_bf);
  64. void Update(const double *pu); // update in the imu reference
  65. void UpdateW(const double *pu); // update in the world reference
  66. Eigen::Vector2d Project(const Eigen::Vector3d &Xw, int cam_idx=0) const; // Mono
  67. Eigen::Vector3d ProjectStereo(const Eigen::Vector3d &Xw, int cam_idx=0) const; // Stereo
  68. bool isDepthPositive(const Eigen::Vector3d &Xw, int cam_idx=0) const;
  69. public:
  70. // For IMU
  71. Eigen::Matrix3d Rwb;
  72. Eigen::Vector3d twb;
  73. // For set of cameras
  74. std::vector<Eigen::Matrix3d> Rcw;
  75. std::vector<Eigen::Vector3d> tcw;
  76. std::vector<Eigen::Matrix3d> Rcb, Rbc;
  77. std::vector<Eigen::Vector3d> tcb, tbc;
  78. double bf;
  79. std::vector<GeometricCamera*> pCamera;
  80. // For posegraph 4DoF
  81. Eigen::Matrix3d Rwb0;
  82. Eigen::Matrix3d DR;
  83. int its;
  84. };
  85. class InvDepthPoint
  86. {
  87. public:
  88. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  89. InvDepthPoint(){}
  90. InvDepthPoint(double _rho, double _u, double _v, KeyFrame* pHostKF);
  91. void Update(const double *pu);
  92. double rho;
  93. double u, v; // they are not variables, observation in the host frame
  94. double fx, fy, cx, cy, bf; // from host frame
  95. int its;
  96. };
  97. // Optimizable parameters are IMU pose
  98. class VertexPose : public g2o::BaseVertex<6,ImuCamPose>
  99. {
  100. public:
  101. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  102. VertexPose(){}
  103. VertexPose(KeyFrame* pKF){
  104. setEstimate(ImuCamPose(pKF));
  105. }
  106. VertexPose(Frame* pF){
  107. setEstimate(ImuCamPose(pF));
  108. }
  109. virtual bool read(std::istream& is);
  110. virtual bool write(std::ostream& os) const;
  111. virtual void setToOriginImpl() {
  112. }
  113. virtual void oplusImpl(const double* update_){
  114. _estimate.Update(update_);
  115. updateCache();
  116. }
  117. };
  118. class VertexPose4DoF : public g2o::BaseVertex<4,ImuCamPose>
  119. {
  120. // Translation and yaw are the only optimizable variables
  121. public:
  122. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  123. VertexPose4DoF(){}
  124. VertexPose4DoF(KeyFrame* pKF){
  125. setEstimate(ImuCamPose(pKF));
  126. }
  127. VertexPose4DoF(Frame* pF){
  128. setEstimate(ImuCamPose(pF));
  129. }
  130. VertexPose4DoF(Eigen::Matrix3d &_Rwc, Eigen::Vector3d &_twc, KeyFrame* pKF){
  131. setEstimate(ImuCamPose(_Rwc, _twc, pKF));
  132. }
  133. virtual bool read(std::istream& is){return false;}
  134. virtual bool write(std::ostream& os) const{return false;}
  135. virtual void setToOriginImpl() {
  136. }
  137. virtual void oplusImpl(const double* update_){
  138. double update6DoF[6];
  139. update6DoF[0] = 0;
  140. update6DoF[1] = 0;
  141. update6DoF[2] = update_[0];
  142. update6DoF[3] = update_[1];
  143. update6DoF[4] = update_[2];
  144. update6DoF[5] = update_[3];
  145. _estimate.UpdateW(update6DoF);
  146. updateCache();
  147. }
  148. };
  149. class VertexVelocity : public g2o::BaseVertex<3,Eigen::Vector3d>
  150. {
  151. public:
  152. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  153. VertexVelocity(){}
  154. VertexVelocity(KeyFrame* pKF);
  155. VertexVelocity(Frame* pF);
  156. virtual bool read(std::istream& is){return false;}
  157. virtual bool write(std::ostream& os) const{return false;}
  158. virtual void setToOriginImpl() {
  159. }
  160. virtual void oplusImpl(const double* update_){
  161. Eigen::Vector3d uv;
  162. uv << update_[0], update_[1], update_[2];
  163. setEstimate(estimate()+uv);
  164. }
  165. };
  166. class VertexGyroBias : public g2o::BaseVertex<3,Eigen::Vector3d>
  167. {
  168. public:
  169. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  170. VertexGyroBias(){}
  171. VertexGyroBias(KeyFrame* pKF);
  172. VertexGyroBias(Frame* pF);
  173. virtual bool read(std::istream& is){return false;}
  174. virtual bool write(std::ostream& os) const{return false;}
  175. virtual void setToOriginImpl() {
  176. }
  177. virtual void oplusImpl(const double* update_){
  178. Eigen::Vector3d ubg;
  179. ubg << update_[0], update_[1], update_[2];
  180. setEstimate(estimate()+ubg);
  181. }
  182. };
  183. class VertexAccBias : public g2o::BaseVertex<3,Eigen::Vector3d>
  184. {
  185. public:
  186. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  187. VertexAccBias(){}
  188. VertexAccBias(KeyFrame* pKF);
  189. VertexAccBias(Frame* pF);
  190. virtual bool read(std::istream& is){return false;}
  191. virtual bool write(std::ostream& os) const{return false;}
  192. virtual void setToOriginImpl() {
  193. }
  194. virtual void oplusImpl(const double* update_){
  195. Eigen::Vector3d uba;
  196. uba << update_[0], update_[1], update_[2];
  197. setEstimate(estimate()+uba);
  198. }
  199. };
  200. // Gravity direction vertex
  201. class GDirection
  202. {
  203. public:
  204. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  205. GDirection(){}
  206. GDirection(Eigen::Matrix3d pRwg): Rwg(pRwg){}
  207. void Update(const double *pu)
  208. {
  209. Rwg=Rwg*ExpSO3(pu[0],pu[1],0.0);
  210. }
  211. Eigen::Matrix3d Rwg, Rgw;
  212. int its;
  213. };
  214. class VertexGDir : public g2o::BaseVertex<2,GDirection>
  215. {
  216. public:
  217. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  218. VertexGDir(){}
  219. VertexGDir(Eigen::Matrix3d pRwg){
  220. setEstimate(GDirection(pRwg));
  221. }
  222. virtual bool read(std::istream& is){return false;}
  223. virtual bool write(std::ostream& os) const{return false;}
  224. virtual void setToOriginImpl() {
  225. }
  226. virtual void oplusImpl(const double* update_){
  227. _estimate.Update(update_);
  228. updateCache();
  229. }
  230. };
  231. // scale vertex
  232. class VertexScale : public g2o::BaseVertex<1,double>
  233. {
  234. public:
  235. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  236. VertexScale(){
  237. setEstimate(1.0);
  238. }
  239. VertexScale(double ps){
  240. setEstimate(ps);
  241. }
  242. virtual bool read(std::istream& is){return false;}
  243. virtual bool write(std::ostream& os) const{return false;}
  244. virtual void setToOriginImpl(){
  245. setEstimate(1.0);
  246. }
  247. virtual void oplusImpl(const double *update_){
  248. setEstimate(estimate()*exp(*update_));
  249. }
  250. };
  251. // Inverse depth point (just one parameter, inverse depth at the host frame)
  252. class VertexInvDepth : public g2o::BaseVertex<1,InvDepthPoint>
  253. {
  254. public:
  255. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  256. VertexInvDepth(){}
  257. VertexInvDepth(double invDepth, double u, double v, KeyFrame* pHostKF){
  258. setEstimate(InvDepthPoint(invDepth, u, v, pHostKF));
  259. }
  260. virtual bool read(std::istream& is){return false;}
  261. virtual bool write(std::ostream& os) const{return false;}
  262. virtual void setToOriginImpl() {
  263. }
  264. virtual void oplusImpl(const double* update_){
  265. _estimate.Update(update_);
  266. updateCache();
  267. }
  268. };
  269. class EdgeMono : public g2o::BaseBinaryEdge<2,Eigen::Vector2d,g2o::VertexSBAPointXYZ,VertexPose>
  270. {
  271. public:
  272. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  273. EdgeMono(int cam_idx_=0): cam_idx(cam_idx_){
  274. }
  275. virtual bool read(std::istream& is){return false;}
  276. virtual bool write(std::ostream& os) const{return false;}
  277. void computeError(){
  278. const g2o::VertexSBAPointXYZ* VPoint = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  279. const VertexPose* VPose = static_cast<const VertexPose*>(_vertices[1]);
  280. const Eigen::Vector2d obs(_measurement);
  281. _error = obs - VPose->estimate().Project(VPoint->estimate(),cam_idx);
  282. }
  283. virtual void linearizeOplus();
  284. bool isDepthPositive()
  285. {
  286. const g2o::VertexSBAPointXYZ* VPoint = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  287. const VertexPose* VPose = static_cast<const VertexPose*>(_vertices[1]);
  288. return VPose->estimate().isDepthPositive(VPoint->estimate(),cam_idx);
  289. }
  290. Eigen::Matrix<double,2,9> GetJacobian(){
  291. linearizeOplus();
  292. Eigen::Matrix<double,2,9> J;
  293. J.block<2,3>(0,0) = _jacobianOplusXi;
  294. J.block<2,6>(0,3) = _jacobianOplusXj;
  295. return J;
  296. }
  297. Eigen::Matrix<double,9,9> GetHessian(){
  298. linearizeOplus();
  299. Eigen::Matrix<double,2,9> J;
  300. J.block<2,3>(0,0) = _jacobianOplusXi;
  301. J.block<2,6>(0,3) = _jacobianOplusXj;
  302. return J.transpose()*information()*J;
  303. }
  304. public:
  305. const int cam_idx;
  306. };
  307. class EdgeMonoOnlyPose : public g2o::BaseUnaryEdge<2,Eigen::Vector2d,VertexPose>
  308. {
  309. public:
  310. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  311. EdgeMonoOnlyPose(const cv::Mat &Xw_, int cam_idx_=0):Xw(Converter::toVector3d(Xw_)),
  312. cam_idx(cam_idx_){}
  313. virtual bool read(std::istream& is){return false;}
  314. virtual bool write(std::ostream& os) const{return false;}
  315. void computeError(){
  316. const VertexPose* VPose = static_cast<const VertexPose*>(_vertices[0]);
  317. const Eigen::Vector2d obs(_measurement);
  318. _error = obs - VPose->estimate().Project(Xw,cam_idx);
  319. }
  320. virtual void linearizeOplus();
  321. bool isDepthPositive()
  322. {
  323. const VertexPose* VPose = static_cast<const VertexPose*>(_vertices[0]);
  324. return VPose->estimate().isDepthPositive(Xw,cam_idx);
  325. }
  326. Eigen::Matrix<double,6,6> GetHessian(){
  327. linearizeOplus();
  328. return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi;
  329. }
  330. public:
  331. const Eigen::Vector3d Xw;
  332. const int cam_idx;
  333. };
  334. class EdgeStereo : public g2o::BaseBinaryEdge<3,Eigen::Vector3d,g2o::VertexSBAPointXYZ,VertexPose>
  335. {
  336. public:
  337. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  338. EdgeStereo(int cam_idx_=0): cam_idx(cam_idx_){}
  339. virtual bool read(std::istream& is){return false;}
  340. virtual bool write(std::ostream& os) const{return false;}
  341. void computeError(){
  342. const g2o::VertexSBAPointXYZ* VPoint = static_cast<const g2o::VertexSBAPointXYZ*>(_vertices[0]);
  343. const VertexPose* VPose = static_cast<const VertexPose*>(_vertices[1]);
  344. const Eigen::Vector3d obs(_measurement);
  345. _error = obs - VPose->estimate().ProjectStereo(VPoint->estimate(),cam_idx);
  346. }
  347. virtual void linearizeOplus();
  348. Eigen::Matrix<double,3,9> GetJacobian(){
  349. linearizeOplus();
  350. Eigen::Matrix<double,3,9> J;
  351. J.block<3,3>(0,0) = _jacobianOplusXi;
  352. J.block<3,6>(0,3) = _jacobianOplusXj;
  353. return J;
  354. }
  355. Eigen::Matrix<double,9,9> GetHessian(){
  356. linearizeOplus();
  357. Eigen::Matrix<double,3,9> J;
  358. J.block<3,3>(0,0) = _jacobianOplusXi;
  359. J.block<3,6>(0,3) = _jacobianOplusXj;
  360. return J.transpose()*information()*J;
  361. }
  362. public:
  363. const int cam_idx;
  364. };
  365. class EdgeStereoOnlyPose : public g2o::BaseUnaryEdge<3,Eigen::Vector3d,VertexPose>
  366. {
  367. public:
  368. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  369. EdgeStereoOnlyPose(const cv::Mat &Xw_, int cam_idx_=0):
  370. Xw(Converter::toVector3d(Xw_)), cam_idx(cam_idx_){}
  371. virtual bool read(std::istream& is){return false;}
  372. virtual bool write(std::ostream& os) const{return false;}
  373. void computeError(){
  374. const VertexPose* VPose = static_cast<const VertexPose*>(_vertices[0]);
  375. const Eigen::Vector3d obs(_measurement);
  376. _error = obs - VPose->estimate().ProjectStereo(Xw, cam_idx);
  377. }
  378. virtual void linearizeOplus();
  379. Eigen::Matrix<double,6,6> GetHessian(){
  380. linearizeOplus();
  381. return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi;
  382. }
  383. public:
  384. const Eigen::Vector3d Xw; // 3D point coordinates
  385. const int cam_idx;
  386. };
  387. class EdgeInertial : public g2o::BaseMultiEdge<9,Vector9d>
  388. {
  389. public:
  390. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  391. EdgeInertial(IMU::Preintegrated* pInt);
  392. virtual bool read(std::istream& is){return false;}
  393. virtual bool write(std::ostream& os) const{return false;}
  394. void computeError();
  395. virtual void linearizeOplus();
  396. Eigen::Matrix<double,24,24> GetHessian(){
  397. linearizeOplus();
  398. Eigen::Matrix<double,9,24> J;
  399. J.block<9,6>(0,0) = _jacobianOplus[0];
  400. J.block<9,3>(0,6) = _jacobianOplus[1];
  401. J.block<9,3>(0,9) = _jacobianOplus[2];
  402. J.block<9,3>(0,12) = _jacobianOplus[3];
  403. J.block<9,6>(0,15) = _jacobianOplus[4];
  404. J.block<9,3>(0,21) = _jacobianOplus[5];
  405. return J.transpose()*information()*J;
  406. }
  407. Eigen::Matrix<double,18,18> GetHessianNoPose1(){
  408. linearizeOplus();
  409. Eigen::Matrix<double,9,18> J;
  410. J.block<9,3>(0,0) = _jacobianOplus[1];
  411. J.block<9,3>(0,3) = _jacobianOplus[2];
  412. J.block<9,3>(0,6) = _jacobianOplus[3];
  413. J.block<9,6>(0,9) = _jacobianOplus[4];
  414. J.block<9,3>(0,15) = _jacobianOplus[5];
  415. return J.transpose()*information()*J;
  416. }
  417. Eigen::Matrix<double,9,9> GetHessian2(){
  418. linearizeOplus();
  419. Eigen::Matrix<double,9,9> J;
  420. J.block<9,6>(0,0) = _jacobianOplus[4];
  421. J.block<9,3>(0,6) = _jacobianOplus[5];
  422. return J.transpose()*information()*J;
  423. }
  424. const Eigen::Matrix3d JRg, JVg, JPg;
  425. const Eigen::Matrix3d JVa, JPa;
  426. IMU::Preintegrated* mpInt;
  427. const double dt;
  428. Eigen::Vector3d g;
  429. };
  430. // Edge inertial whre gravity is included as optimizable variable and it is not supposed to be pointing in -z axis, as well as scale
  431. class EdgeInertialGS : public g2o::BaseMultiEdge<9,Vector9d>
  432. {
  433. public:
  434. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  435. // EdgeInertialGS(IMU::Preintegrated* pInt);
  436. EdgeInertialGS(IMU::Preintegrated* pInt);
  437. virtual bool read(std::istream& is){return false;}
  438. virtual bool write(std::ostream& os) const{return false;}
  439. void computeError();
  440. virtual void linearizeOplus();
  441. const Eigen::Matrix3d JRg, JVg, JPg;
  442. const Eigen::Matrix3d JVa, JPa;
  443. IMU::Preintegrated* mpInt;
  444. const double dt;
  445. Eigen::Vector3d g, gI;
  446. Eigen::Matrix<double,27,27> GetHessian(){
  447. linearizeOplus();
  448. Eigen::Matrix<double,9,27> J;
  449. J.block<9,6>(0,0) = _jacobianOplus[0];
  450. J.block<9,3>(0,6) = _jacobianOplus[1];
  451. J.block<9,3>(0,9) = _jacobianOplus[2];
  452. J.block<9,3>(0,12) = _jacobianOplus[3];
  453. J.block<9,6>(0,15) = _jacobianOplus[4];
  454. J.block<9,3>(0,21) = _jacobianOplus[5];
  455. J.block<9,2>(0,24) = _jacobianOplus[6];
  456. J.block<9,1>(0,26) = _jacobianOplus[7];
  457. return J.transpose()*information()*J;
  458. }
  459. Eigen::Matrix<double,27,27> GetHessian2(){
  460. linearizeOplus();
  461. Eigen::Matrix<double,9,27> J;
  462. J.block<9,3>(0,0) = _jacobianOplus[2];
  463. J.block<9,3>(0,3) = _jacobianOplus[3];
  464. J.block<9,2>(0,6) = _jacobianOplus[6];
  465. J.block<9,1>(0,8) = _jacobianOplus[7];
  466. J.block<9,3>(0,9) = _jacobianOplus[1];
  467. J.block<9,3>(0,12) = _jacobianOplus[5];
  468. J.block<9,6>(0,15) = _jacobianOplus[0];
  469. J.block<9,6>(0,21) = _jacobianOplus[4];
  470. return J.transpose()*information()*J;
  471. }
  472. Eigen::Matrix<double,9,9> GetHessian3(){
  473. linearizeOplus();
  474. Eigen::Matrix<double,9,9> J;
  475. J.block<9,3>(0,0) = _jacobianOplus[2];
  476. J.block<9,3>(0,3) = _jacobianOplus[3];
  477. J.block<9,2>(0,6) = _jacobianOplus[6];
  478. J.block<9,1>(0,8) = _jacobianOplus[7];
  479. return J.transpose()*information()*J;
  480. }
  481. Eigen::Matrix<double,1,1> GetHessianScale(){
  482. linearizeOplus();
  483. Eigen::Matrix<double,9,1> J = _jacobianOplus[7];
  484. return J.transpose()*information()*J;
  485. }
  486. Eigen::Matrix<double,3,3> GetHessianBiasGyro(){
  487. linearizeOplus();
  488. Eigen::Matrix<double,9,3> J = _jacobianOplus[2];
  489. return J.transpose()*information()*J;
  490. }
  491. Eigen::Matrix<double,3,3> GetHessianBiasAcc(){
  492. linearizeOplus();
  493. Eigen::Matrix<double,9,3> J = _jacobianOplus[3];
  494. return J.transpose()*information()*J;
  495. }
  496. Eigen::Matrix<double,2,2> GetHessianGDir(){
  497. linearizeOplus();
  498. Eigen::Matrix<double,9,2> J = _jacobianOplus[6];
  499. return J.transpose()*information()*J;
  500. }
  501. };
  502. class EdgeGyroRW : public g2o::BaseBinaryEdge<3,Eigen::Vector3d,VertexGyroBias,VertexGyroBias>
  503. {
  504. public:
  505. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  506. EdgeGyroRW(){}
  507. virtual bool read(std::istream& is){return false;}
  508. virtual bool write(std::ostream& os) const{return false;}
  509. void computeError(){
  510. const VertexGyroBias* VG1= static_cast<const VertexGyroBias*>(_vertices[0]);
  511. const VertexGyroBias* VG2= static_cast<const VertexGyroBias*>(_vertices[1]);
  512. _error = VG2->estimate()-VG1->estimate();
  513. }
  514. virtual void linearizeOplus(){
  515. _jacobianOplusXi = -Eigen::Matrix3d::Identity();
  516. _jacobianOplusXj.setIdentity();
  517. }
  518. Eigen::Matrix<double,6,6> GetHessian(){
  519. linearizeOplus();
  520. Eigen::Matrix<double,3,6> J;
  521. J.block<3,3>(0,0) = _jacobianOplusXi;
  522. J.block<3,3>(0,3) = _jacobianOplusXj;
  523. return J.transpose()*information()*J;
  524. }
  525. Eigen::Matrix3d GetHessian2(){
  526. linearizeOplus();
  527. return _jacobianOplusXj.transpose()*information()*_jacobianOplusXj;
  528. }
  529. };
  530. class EdgeAccRW : public g2o::BaseBinaryEdge<3,Eigen::Vector3d,VertexAccBias,VertexAccBias>
  531. {
  532. public:
  533. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  534. EdgeAccRW(){}
  535. virtual bool read(std::istream& is){return false;}
  536. virtual bool write(std::ostream& os) const{return false;}
  537. void computeError(){
  538. const VertexGyroBias* VG1= static_cast<const VertexGyroBias*>(_vertices[0]);
  539. const VertexGyroBias* VG2= static_cast<const VertexGyroBias*>(_vertices[1]);
  540. _error = VG2->estimate()-VG1->estimate();
  541. }
  542. virtual void linearizeOplus(){
  543. _jacobianOplusXi = -Eigen::Matrix3d::Identity();
  544. _jacobianOplusXj.setIdentity();
  545. }
  546. Eigen::Matrix<double,6,6> GetHessian(){
  547. linearizeOplus();
  548. Eigen::Matrix<double,3,6> J;
  549. J.block<3,3>(0,0) = _jacobianOplusXi;
  550. J.block<3,3>(0,3) = _jacobianOplusXj;
  551. return J.transpose()*information()*J;
  552. }
  553. Eigen::Matrix3d GetHessian2(){
  554. linearizeOplus();
  555. return _jacobianOplusXj.transpose()*information()*_jacobianOplusXj;
  556. }
  557. };
  558. class ConstraintPoseImu
  559. {
  560. public:
  561. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  562. ConstraintPoseImu(const Eigen::Matrix3d &Rwb_, const Eigen::Vector3d &twb_, const Eigen::Vector3d &vwb_,
  563. const Eigen::Vector3d &bg_, const Eigen::Vector3d &ba_, const Matrix15d &H_):
  564. Rwb(Rwb_), twb(twb_), vwb(vwb_), bg(bg_), ba(ba_), H(H_)
  565. {
  566. H = (H+H)/2;
  567. Eigen::SelfAdjointEigenSolver<Eigen::Matrix<double,15,15> > es(H);
  568. Eigen::Matrix<double,15,1> eigs = es.eigenvalues();
  569. for(int i=0;i<15;i++)
  570. if(eigs[i]<1e-12)
  571. eigs[i]=0;
  572. H = es.eigenvectors()*eigs.asDiagonal()*es.eigenvectors().transpose();
  573. }
  574. ConstraintPoseImu(const cv::Mat &Rwb_, const cv::Mat &twb_, const cv::Mat &vwb_,
  575. const IMU::Bias &b, const cv::Mat &H_)
  576. {
  577. Rwb = Converter::toMatrix3d(Rwb_);
  578. twb = Converter::toVector3d(twb_);
  579. vwb = Converter::toVector3d(vwb_);
  580. bg << b.bwx, b.bwy, b.bwz;
  581. ba << b.bax, b.bay, b.baz;
  582. for(int i=0;i<15;i++)
  583. for(int j=0;j<15;j++)
  584. H(i,j)=H_.at<float>(i,j);
  585. H = (H+H)/2;
  586. Eigen::SelfAdjointEigenSolver<Eigen::Matrix<double,15,15> > es(H);
  587. Eigen::Matrix<double,15,1> eigs = es.eigenvalues();
  588. for(int i=0;i<15;i++)
  589. if(eigs[i]<1e-12)
  590. eigs[i]=0;
  591. H = es.eigenvectors()*eigs.asDiagonal()*es.eigenvectors().transpose();
  592. }
  593. Eigen::Matrix3d Rwb;
  594. Eigen::Vector3d twb;
  595. Eigen::Vector3d vwb;
  596. Eigen::Vector3d bg;
  597. Eigen::Vector3d ba;
  598. Matrix15d H;
  599. };
  600. class EdgePriorPoseImu : public g2o::BaseMultiEdge<15,Vector15d>
  601. {
  602. public:
  603. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  604. EdgePriorPoseImu(ConstraintPoseImu* c);
  605. virtual bool read(std::istream& is){return false;}
  606. virtual bool write(std::ostream& os) const{return false;}
  607. void computeError();
  608. virtual void linearizeOplus();
  609. Eigen::Matrix<double,15,15> GetHessian(){
  610. linearizeOplus();
  611. Eigen::Matrix<double,15,15> J;
  612. J.block<15,6>(0,0) = _jacobianOplus[0];
  613. J.block<15,3>(0,6) = _jacobianOplus[1];
  614. J.block<15,3>(0,9) = _jacobianOplus[2];
  615. J.block<15,3>(0,12) = _jacobianOplus[3];
  616. return J.transpose()*information()*J;
  617. }
  618. Eigen::Matrix<double,9,9> GetHessianNoPose(){
  619. linearizeOplus();
  620. Eigen::Matrix<double,15,9> J;
  621. J.block<15,3>(0,0) = _jacobianOplus[1];
  622. J.block<15,3>(0,3) = _jacobianOplus[2];
  623. J.block<15,3>(0,6) = _jacobianOplus[3];
  624. return J.transpose()*information()*J;
  625. }
  626. Eigen::Matrix3d Rwb;
  627. Eigen::Vector3d twb, vwb;
  628. Eigen::Vector3d bg, ba;
  629. };
  630. // Priors for biases
  631. class EdgePriorAcc : public g2o::BaseUnaryEdge<3,Eigen::Vector3d,VertexAccBias>
  632. {
  633. public:
  634. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  635. EdgePriorAcc(const cv::Mat &bprior_):bprior(Converter::toVector3d(bprior_)){}
  636. virtual bool read(std::istream& is){return false;}
  637. virtual bool write(std::ostream& os) const{return false;}
  638. void computeError(){
  639. const VertexAccBias* VA = static_cast<const VertexAccBias*>(_vertices[0]);
  640. _error = bprior - VA->estimate();
  641. }
  642. virtual void linearizeOplus();
  643. Eigen::Matrix<double,3,3> GetHessian(){
  644. linearizeOplus();
  645. return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi;
  646. }
  647. const Eigen::Vector3d bprior;
  648. };
  649. class EdgePriorGyro : public g2o::BaseUnaryEdge<3,Eigen::Vector3d,VertexGyroBias>
  650. {
  651. public:
  652. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  653. EdgePriorGyro(const cv::Mat &bprior_):bprior(Converter::toVector3d(bprior_)){}
  654. virtual bool read(std::istream& is){return false;}
  655. virtual bool write(std::ostream& os) const{return false;}
  656. void computeError(){
  657. const VertexGyroBias* VG = static_cast<const VertexGyroBias*>(_vertices[0]);
  658. _error = bprior - VG->estimate();
  659. }
  660. virtual void linearizeOplus();
  661. Eigen::Matrix<double,3,3> GetHessian(){
  662. linearizeOplus();
  663. return _jacobianOplusXi.transpose()*information()*_jacobianOplusXi;
  664. }
  665. const Eigen::Vector3d bprior;
  666. };
  667. class Edge4DoF : public g2o::BaseBinaryEdge<6,Vector6d,VertexPose4DoF,VertexPose4DoF>
  668. {
  669. public:
  670. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  671. Edge4DoF(const Eigen::Matrix4d &deltaT){
  672. dTij = deltaT;
  673. dRij = deltaT.block<3,3>(0,0);
  674. dtij = deltaT.block<3,1>(0,3);
  675. }
  676. virtual bool read(std::istream& is){return false;}
  677. virtual bool write(std::ostream& os) const{return false;}
  678. void computeError(){
  679. const VertexPose4DoF* VPi = static_cast<const VertexPose4DoF*>(_vertices[0]);
  680. const VertexPose4DoF* VPj = static_cast<const VertexPose4DoF*>(_vertices[1]);
  681. _error << LogSO3(VPi->estimate().Rcw[0]*VPj->estimate().Rcw[0].transpose()*dRij.transpose()),
  682. VPi->estimate().Rcw[0]*(-VPj->estimate().Rcw[0].transpose()*VPj->estimate().tcw[0])+VPi->estimate().tcw[0] - dtij;
  683. }
  684. // virtual void linearizeOplus(); // numerical implementation
  685. Eigen::Matrix4d dTij;
  686. Eigen::Matrix3d dRij;
  687. Eigen::Vector3d dtij;
  688. };
  689. } //namespace ORB_SLAM2
  690. #endif // G2OTYPES_H