Static Public Member Functions | List of all members
ORB_SLAM2::Optimizer Class Reference

#include <Optimizer.h>

Static Public Member Functions

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)
 

Detailed Description

Definition at line 37 of file Optimizer.h.

Member Function Documentation

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

Definition at line 49 of file Optimizer.cc.

void ORB_SLAM2::Optimizer::GlobalBundleAdjustemnt ( Map pMap,
int  nIterations = 5,
bool *  pbStopFlag = NULL,
const unsigned long  nLoopKF = 0,
const bool  bRobust = true 
)
static

Definition at line 41 of file Optimizer.cc.

void ORB_SLAM2::Optimizer::LocalBundleAdjustment ( KeyFrame pKF,
bool *  pbStopFlag,
Map pMap 
)
static

Definition at line 453 of file Optimizer.cc.

void ORB_SLAM2::Optimizer::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

Definition at line 781 of file Optimizer.cc.

int ORB_SLAM2::Optimizer::OptimizeSim3 ( KeyFrame pKF1,
KeyFrame pKF2,
std::vector< MapPoint * > &  vpMatches1,
g2o::Sim3 g2oS12,
const float  th2,
const bool  bFixScale 
)
static

Definition at line 1046 of file Optimizer.cc.

int ORB_SLAM2::Optimizer::PoseOptimization ( Frame pFrame)
static

Definition at line 239 of file Optimizer.cc.


The documentation for this class was generated from the following files:


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