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);
44 const unsigned long nLoopKF=0,
const bool bRobust =
true);
52 const map<
KeyFrame *, set<KeyFrame *> > &LoopConnections,
53 const bool &bFixScale);
57 g2o::Sim3 &g2oS12,
const float th2,
const bool bFixScale);
static void LocalBundleAdjustment(KeyFrame *pKF, bool *pbStopFlag, Map *pMap)
static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale)
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)
map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< const KeyFrame *, g2o::Sim3 > > > KeyFrameAndPose
static int PoseOptimization(Frame *pFrame)
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)