《视觉SLAM十四讲》第六讲g2o曲线拟合报错解决办法

一、报错信息:

/home/xxx/slambook/ch6/g2o_curve_fitting/main.cpp: In function ‘int main(int, char**):
/home/xxx/slambook/ch6/g2o_curve_fitting/main.cpp:77:49: error: no matching function for call to ‘g2o::BlockSolver<g2o::BlockSolverTraits<3, 1> >::BlockSolver(g2o::BlockSolver<g2o::BlockSolverTraits<3, 1> >::LinearSolverType*&)’
     Block* solver_ptr = new Block( linearSolver );      // 矩阵块求解器
                                                 ^
In file included from /usr/local/include/g2o/core/block_solver.h:199:0,
                 from /home/xxx/slambook/ch6/g2o_curve_fitting/main.cpp:4:
/usr/local/include/g2o/core/block_solver.hpp:40:1: note: candidate: g2o::BlockSolver<Traits>::BlockSolver(std::unique_ptr<typename Traits::LinearSolverType>) [with Traits = g2o::BlockSolverTraits<3, 1>; typename Traits::LinearSolverType = g2o::LinearSolver<Eigen::Matrix<double, 3, 3> >]
 BlockSolver<Traits>::BlockSolver(std::unique_ptr<LinearSolverType> linearSolver
 ^
/usr/local/include/g2o/core/block_solver.hpp:40:1: note:   no known conversion for argument 1 from ‘g2o::BlockSolver<g2o::BlockSolverTraits<3, 1> >::LinearSolverType* {aka g2o::LinearSolver<Eigen::Matrix<double, 3, 3> >*}’ to ‘std::unique_ptr<g2o::LinearSolver<Eigen::Matrix<double, 3, 3> >, std::default_delete<g2o::LinearSolver<Eigen::Matrix<double, 3, 3> > > >/home/xxx/slambook/ch6/g2o_curve_fitting/main.cpp:79:103: error: no matching function for call to ‘g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(Block*&)’
 rithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( solver_ptr );
                                                                              ^
In file included from /home/xxx/slambook/ch6/g2o_curve_fitting/main.cpp:5:0:
/usr/local/include/g2o/core/optimization_algorithm_levenberg.h:47:16: note: candidate: g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(std::unique_ptr<g2o::Solver>)
       explicit OptimizationAlgorithmLevenberg(std::unique_ptr<Solver> solver);
                ^
/usr/local/include/g2o/core/optimization_algorithm_levenberg.h:47:16: note:   no known conversion for argument 1 from ‘Block* {aka g2o::BlockSolver<g2o::BlockSolverTraits<3, 1> >*}’ to ‘std::unique_ptr<g2o::Solver>’
CMakeFiles/curve_fitting.dir/build.make:62: recipe for target 'CMakeFiles/curve_fitting.dir/main.cpp.o' failed
make[2]: *** [CMakeFiles/curve_fitting.dir/main.cpp.o] Error 1
CMakeFiles/Makefile2:67: recipe for target 'CMakeFiles/curve_fitting.dir/all' failed
make[1]: *** [CMakeFiles/curve_fitting.dir/all] Error 2
Makefile:83: recipe for target 'all' failed
make: *** [all] Error 2

二、出错原因

g2o新版本和旧版本不兼容。
https://github.com/winnerineast/g2o/blob/master/g2o/core/block_solver.h
旧版本:

      BlockSolver(LinearSolverType* linearSolver);
      ~BlockSolver();

新版本:

      BlockSolver(std::unique_ptr<LinearSolverType> linearSolver);
      ~BlockSolver();

三、解决办法

方法一:

使用SLAM十四讲代码中附带的第三方库文件夹下的g2o旧版本;

方法二:

main.cpp中出错部分代码:

	    // 构建图优化,先设定g2o
    typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block;  // 每个误差项优化变量维度为3,误差值维度为1
    Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense<Block::PoseMatrixType>(); // 线性方程求解器
    Block* solver_ptr = new Block( linearSolver );      // 矩阵块求解器
    // 梯度下降方法,从GN, LM, DogLeg 中选
    g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( solver_ptr );
    // g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton( solver_ptr );
    // g2o::OptimizationAlgorithmDogleg* solver = new g2o::OptimizationAlgorithmDogleg( solver_ptr );
    g2o::SparseOptimizer optimizer;     // 图模型
    optimizer.setAlgorithm( solver );   // 设置求解器
    optimizer.setVerbose( true );       // 打开调试输出

修改为:

	// 构建图优化,先设定g2o
    typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block;  // 每个误差项优化变量维度为3,误差值维度为1
    std::unique_ptr<Block::LinearSolverType> linearSolver(new g2o::LinearSolverDense<Block::PoseMatrixType>()); // 线性方程求解器
    std::unique_ptr<Block> solver_ptr (new Block(std::move(linearSolver)));      // 矩阵块求解器
    // 梯度下降方法,从GN, LM, DogLeg 中选
    g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(solver_ptr));
    // g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton(std::move(solver_ptr));
    // g2o::OptimizationAlgorithmDogleg* solver = new g2o::OptimizationAlgorithmDogleg(std::move(solver_ptr));
    g2o::SparseOptimizer optimizer;     // 图模型
    optimizer.setAlgorithm( solver );   // 设置求解器
    optimizer.setVerbose( true );       // 打开调试输出

同样的,关于第七章pose_estimation_3d2d.cpp,pose_estimation_3d3d.cpp报错部分代码也需做类似修改。


参考其他博客:
https://www.cnblogs.com/xueyuanaichiyu/p/7921382.html
https://blog.csdn.net/Amazingren/article/details/81774784?utm_source=blogxgwz1

你可能感兴趣的:(slam,c++)