《视觉SLAM十四讲》第六讲g2o实践代码报错解决方法

问题:

首先贴出报错部分代码:

typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block; 
Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense<Block::PoseMatrixType>(); 
Block* solver_ptr = new Block( linearSolver );     
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( solver_ptr );
g2o::SparseOptimizer optimizer;   
optimizer.setAlgorithm( solver );   
optimizer.setVerbose( true ); 

按照书上的例程编写代码,编译时报错(部分截图)如下:

/home/wxy/slambook/useg2o/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 );      
                                             ^
/home/wxy/slambook/useg2o/main.cpp:77:49: note: candidate is:
In file included from     /usr/local/include/g2o/core/block_solver.h:199:0,
             from /home/wxy/slambook/useg2o/main.cpp:4:
/usr/local/include/g2o/core/block_solver.hpp:40:1: note: 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)

好像是编译器无法找到某个函数,或者某个调用出错。我第一个想到的是无法找到g2o有关函数那应该是g2o库没有装好(这个库我make的时候等了大概两个小时,也不知道为啥会卡这么久)于是将库重装了一下,再次编译还是报错,仔细读报错信息下面有写到:

BlockSolver<Traits>::BlockSolver(std::unique_ptr<LinearSolverType> linearSolver)

会不会是我调用方法不对?网上搜索std::unique_ptr是干嘛用的(c++知识忘得差不多了....),搜到:http://blog.csdn.net/pi9nc/article/details/12227887
原来是智能指针。

unique_ptr“唯一”拥有其所指对象,同一时刻只能有一个unique_ptr指向给定对象(通过禁止拷贝语义、只有移动语义来实现)。

原代码中用到的好像是普通的指针,难道是因为指针类型不匹配?然后我在网上收到了一篇博客:http://blog.csdn.net/robinhjwy/article/details/78084210
惊了,原来有人跟我一样遇到过这种问题,而且早就解决了。。。。修改过后的代码如下:

typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block;
std::unique_ptr<Block::LinearSolverType> linearSolver ( new g2o::LinearSolverDense<Block::PoseMatrixType>() );
std::unique_ptr<Block> solver_ptr (new Block( std::move(linearSolver) ));
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( std::move(solver_ptr) );
g2o::SparseOptimizer optimizer;   
optimizer.setAlgorithm( solver );   
optimizer.setVerbose( true ); 

将初始化中用等号赋值的地方改成用std::unique_ptr赋值,将linearSolver和solver_ptr用移动语言也就是std::move来实现。改完后编译运行成功,意犹未尽的我又去查了一下关于g2o的初始化问题,因为报错的地方就是这里,然后看到了这篇博客:
https://www.cnblogs.com/serser/p/7815588.html

修改代码如下:

typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block;
Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense<Block::PoseMatrixType>();
Block* solver_ptr = new Block( std::unique_ptr<Block::LinearSolverType>(linearSolver) );
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::unique_ptr<Block>(solver_ptr) );
g2o::SparseOptimizer optimizer;   
optimizer.setAlgorithm( solver );   
optimizer.setVerbose( true ); 

前面还是用普通指针来赋值,之后再转换成unique_ptr.
运行结果:

posted on 2017-11-29 16:47  学远爱吃鱼  阅读(17470)  评论(1编辑  收藏  举报

导航