G2oTypes.h 24 KB

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