Optimizer.h
Go to the documentation of this file.
1 
21 #ifndef OPTIMIZER_H
22 #define OPTIMIZER_H
23 
24 #include "Map.h"
25 #include "MapPoint.h"
26 #include "KeyFrame.h"
27 #include "LoopClosing.h"
28 #include "Frame.h"
29 
31 
32 namespace ORB_SLAM2
33 {
34 
35 class LoopClosing;
36 
37 class Optimizer
38 {
39 public:
40  void static BundleAdjustment(const std::vector<KeyFrame*> &vpKF, const std::vector<MapPoint*> &vpMP,
41  int nIterations = 5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0,
42  const bool bRobust = true);
43  void static GlobalBundleAdjustemnt(Map* pMap, int nIterations=5, bool *pbStopFlag=NULL,
44  const unsigned long nLoopKF=0, const bool bRobust = true);
45  void static LocalBundleAdjustment(KeyFrame* pKF, bool *pbStopFlag, Map *pMap);
46  int static PoseOptimization(Frame* pFrame);
47 
48  // if bFixScale is true, 6DoF optimization (stereo,rgbd), 7DoF otherwise (mono)
49  void static OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF,
50  const LoopClosing::KeyFrameAndPose &NonCorrectedSim3,
51  const LoopClosing::KeyFrameAndPose &CorrectedSim3,
52  const map<KeyFrame *, set<KeyFrame *> > &LoopConnections,
53  const bool &bFixScale);
54 
55  // if bFixScale is true, optimize SE3 (stereo,rgbd), Sim3 otherwise (mono)
56  static int OptimizeSim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector<MapPoint *> &vpMatches1,
57  g2o::Sim3 &g2oS12, const float th2, const bool bFixScale);
58 };
59 
60 } //namespace ORB_SLAM
61 
62 #endif // OPTIMIZER_H
Definition: sim3.h:41
static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale)
Definition: Optimizer.cc:1046
map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< KeyFrame *const, g2o::Sim3 > > > KeyFrameAndPose
Definition: LoopClosing.h:50
static void GlobalBundleAdjustemnt(Map *pMap, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
Definition: Optimizer.cc:41
static void OptimizeEssentialGraph(Map *pMap, KeyFrame *pLoopKF, KeyFrame *pCurKF, const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, const LoopClosing::KeyFrameAndPose &CorrectedSim3, const map< KeyFrame *, set< KeyFrame * > > &LoopConnections, const bool &bFixScale)
Definition: Optimizer.cc:781
static void BundleAdjustment(const std::vector< KeyFrame * > &vpKF, const std::vector< MapPoint * > &vpMP, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
Definition: Optimizer.cc:49
static int PoseOptimization(Frame *pFrame)
Definition: Optimizer.cc:239
static void LocalBundleAdjustment(KeyFrame *pKF, bool *pbStopFlag, Map *pMap)
Definition: Optimizer.cc:453


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05