Optimizer.h 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106
  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 OPTIMIZER_H
  19. #define OPTIMIZER_H
  20. #include "Map.h"
  21. #include "MapPoint.h"
  22. #include "KeyFrame.h"
  23. #include "LoopClosing.h"
  24. #include "Frame.h"
  25. #include <math.h>
  26. #include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h"
  27. #include "Thirdparty/g2o/g2o/core/sparse_block_matrix.h"
  28. #include "Thirdparty/g2o/g2o/core/block_solver.h"
  29. #include "Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h"
  30. #include "Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h"
  31. #include "Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h"
  32. #include "Thirdparty/g2o/g2o/types/types_six_dof_expmap.h"
  33. #include "Thirdparty/g2o/g2o/core/robust_kernel_impl.h"
  34. #include "Thirdparty/g2o/g2o/solvers/linear_solver_dense.h"
  35. namespace ORB_SLAM3
  36. {
  37. class LoopClosing;
  38. class Optimizer
  39. {
  40. public:
  41. void static BundleAdjustment(const std::vector<KeyFrame*> &vpKF, const std::vector<MapPoint*> &vpMP,
  42. int nIterations = 5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0,
  43. const bool bRobust = true);
  44. void static GlobalBundleAdjustemnt(Map* pMap, int nIterations=5, bool *pbStopFlag=NULL,
  45. const unsigned long nLoopKF=0, const bool bRobust = true);
  46. void static FullInertialBA(Map *pMap, int its, const bool bFixLocal=false, const unsigned long nLoopKF=0, bool *pbStopFlag=NULL, bool bInit=false, float priorG = 1e2, float priorA=1e6, Eigen::VectorXd *vSingVal = NULL, bool *bHess=NULL);
  47. void static LocalBundleAdjustment(KeyFrame* pKF, bool *pbStopFlag, Map *pMap, int& num_fixedKF, int& num_OptKF, int& num_MPs, int& num_edges);
  48. int static PoseOptimization(Frame* pFrame);
  49. int static PoseInertialOptimizationLastKeyFrame(Frame* pFrame, bool bRecInit = false);
  50. int static PoseInertialOptimizationLastFrame(Frame *pFrame, bool bRecInit = false);
  51. // if bFixScale is true, 6DoF optimization (stereo,rgbd), 7DoF otherwise (mono)
  52. void static OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF,
  53. const LoopClosing::KeyFrameAndPose &NonCorrectedSim3,
  54. const LoopClosing::KeyFrameAndPose &CorrectedSim3,
  55. const map<KeyFrame *, set<KeyFrame *> > &LoopConnections,
  56. const bool &bFixScale);
  57. void static OptimizeEssentialGraph(KeyFrame* pCurKF, vector<KeyFrame*> &vpFixedKFs, vector<KeyFrame*> &vpFixedCorrectedKFs,
  58. vector<KeyFrame*> &vpNonFixedKFs, vector<MapPoint*> &vpNonCorrectedMPs);
  59. // For inertial loopclosing
  60. void static OptimizeEssentialGraph4DoF(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF,
  61. const LoopClosing::KeyFrameAndPose &NonCorrectedSim3,
  62. const LoopClosing::KeyFrameAndPose &CorrectedSim3,
  63. const map<KeyFrame *, set<KeyFrame *> > &LoopConnections);
  64. // if bFixScale is true, optimize SE3 (stereo,rgbd), Sim3 otherwise (mono) (NEW)
  65. static int OptimizeSim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector<MapPoint *> &vpMatches1,
  66. g2o::Sim3 &g2oS12, const float th2, const bool bFixScale,
  67. Eigen::Matrix<double,7,7> &mAcumHessian, const bool bAllPoints=false);
  68. // For inertial systems
  69. void static LocalInertialBA(KeyFrame* pKF, bool *pbStopFlag, Map *pMap, int& num_fixedKF, int& num_OptKF, int& num_MPs, int& num_edges, bool bLarge = false, bool bRecInit = false);
  70. void static MergeInertialBA(KeyFrame* pCurrKF, KeyFrame* pMergeKF, bool *pbStopFlag, Map *pMap, LoopClosing::KeyFrameAndPose &corrPoses);
  71. // Local BA in welding area when two maps are merged
  72. void static LocalBundleAdjustment(KeyFrame* pMainKF,vector<KeyFrame*> vpAdjustKF, vector<KeyFrame*> vpFixedKF, bool *pbStopFlag);
  73. // Marginalize block element (start:end,start:end). Perform Schur complement.
  74. // Marginalized elements are filled with zeros.
  75. static Eigen::MatrixXd Marginalize(const Eigen::MatrixXd &H, const int &start, const int &end);
  76. // Inertial pose-graph
  77. void static InertialOptimization(Map *pMap, Eigen::Matrix3d &Rwg, double &scale, Eigen::Vector3d &bg, Eigen::Vector3d &ba, bool bMono, Eigen::MatrixXd &covInertial, bool bFixedVel=false, bool bGauss=false, float priorG = 1e2, float priorA = 1e6);
  78. void static InertialOptimization(Map *pMap, Eigen::Vector3d &bg, Eigen::Vector3d &ba, float priorG = 1e2, float priorA = 1e6);
  79. void static InertialOptimization(Map *pMap, Eigen::Matrix3d &Rwg, double &scale);
  80. EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
  81. };
  82. } //namespace ORB_SLAM3
  83. #endif // OPTIMIZER_H