#include "Optimizer.h"
|  | 
| 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) | 
|  | 
| static void | GlobalBundleAdjustemnt (Map *pMap, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true) | 
|  | 
| static void | LocalBundleAdjustment (KeyFrame *pKF, bool *pbStopFlag, Map *pMap) | 
|  | 
| 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) | 
|  | 
| static int | OptimizeSim3 (KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint *> &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale) | 
|  | 
| static int | PoseOptimization (Frame *pFrame) | 
|  | 
◆ BundleAdjustment()
  
  | 
        
          | static void ORB_SLAM2::Optimizer::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 |  
          |  | ) |  |  |  | static | 
 
 
◆ GlobalBundleAdjustemnt()
  
  | 
        
          | static void ORB_SLAM2::Optimizer::GlobalBundleAdjustemnt | ( | Map * | pMap, |  
          |  |  | int | nIterations = 5, |  
          |  |  | bool * | pbStopFlag = NULL, |  
          |  |  | const unsigned long | nLoopKF = 0, |  
          |  |  | const bool | bRobust = true |  
          |  | ) |  |  |  | static | 
 
 
◆ LocalBundleAdjustment()
  
  | 
        
          | static void ORB_SLAM2::Optimizer::LocalBundleAdjustment | ( | KeyFrame * | pKF, |  
          |  |  | bool * | pbStopFlag, |  
          |  |  | Map * | pMap |  
          |  | ) |  |  |  | static | 
 
 
◆ OptimizeEssentialGraph()
◆ OptimizeSim3()
  
  | 
        
          | static int ORB_SLAM2::Optimizer::OptimizeSim3 | ( | KeyFrame * | pKF1, |  
          |  |  | KeyFrame * | pKF2, |  
          |  |  | std::vector< MapPoint *> & | vpMatches1, |  
          |  |  | g2o::Sim3 & | g2oS12, |  
          |  |  | const float | th2, |  
          |  |  | const bool | bFixScale |  
          |  | ) |  |  |  | static | 
 
 
◆ PoseOptimization()
  
  | 
        
          | static int ORB_SLAM2::Optimizer::PoseOptimization | ( | Frame * | pFrame | ) |  |  | static | 
 
 
The documentation for this class was generated from the following file: