ORB-SLAM_地图点优化_固定位姿_g2o定义_雅可比矩阵推导
1. 目标
在构建vslam点云地图时,如何固定位姿,仅仅对地图点进行优化的问题。
2. 代码实现
2.1 固定位姿的地图点BA优化
(基于ORB-SLAM2源码)
void Optimizer::BundleAdjustmentFixPose(const vector<std::shared_ptr<KeyFrame>> &vpKFs,const vector<std::shared_ptr<MapPoint>> &vpMP,int nIterations)
{// 1. 初始化g2o优化器g2o::SparseOptimizer optimizer;// 使用 Eigen 作为线性求解器(适配 BlockSolverX 的默认模板)using BlockSolverX = g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1>>;using LinearSolverType = g2o::LinearSolverEigen<BlockSolverX::Pos