gaoxiang12 / slambook

MIT License
6.94k stars 3.27k forks source link

ch6 g2o_curve_fitting. no matching function for call to ... #43

Open shaozu opened 7 years ago

shaozu commented 7 years ago

Those days when I try to compile ch6's g2o code, I got an error with error: no matching function for call to ‘g2o::BlockSolver<g2o::BlockSolverTraits<3, 1>>::BlockSolver(g2o::BlockSolver<g2o::BlockSolverTraits<3, 1> >::LinearSolverType*&). I run the code on a virtual machine with Ubuntu-16.04 installed.

Then I found a solution in g2o's example. See following code.

typedef g2o::BlockSolver<g2o::BlockSolverTraits<3, 1> > Block;
typedef g2o::LinearSolverDense<Block::PoseMatrixType> MyLinearSolver;
// Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense<Block::PoseMatrixType> ();
// Block* solver_ptr = new Block(linearSolver);
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(
        g2o::make_unique<Block>(g2o::make_unique<MyLinearSolver>())
);

I am not sure what's the problem, but anyway it was solved. So I post it here in case you have the same problem.

Thanks for your informative book. 👍

lianchengyue commented 7 years ago

I met the same problem as you got when i got the newest g2o source code from github. use slambook/3rdparty/g2o.tar.gz instead, I have all two errors fixed.

Wish the same useful for you.

suljaxm commented 7 years ago

新版本改掉了这个数据结构,用2017.6月的老版本就行了,高博书里自带的三方库里的g2o也符合

Harry-Zhi commented 7 years ago

@suljaxm 的确,应该是g2o的版本问题。我本来也有同样的问题,之后我删除了github上的最新版本g2o,采用了高博提供的g2o,程序就能正常编译了。

zhkmxx9302013 commented 6 years ago

我也遇到了同样的问题, 新版的g2o,BlockSover的构造器是unique_ptr的,unique_ptr不支持拷贝构造,所以传参必须通过move,我把改的地方发到下面,可供参考。

参考链接1 参考修改代码: 参考链接2 unique_ptr说明: 参考链接3 std::move的使用:

#include <iostream>
#include <g2o/core/base_vertex.h>
#include <g2o/core/base_unary_edge.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/optimization_algorithm_levenberg.h>
#include <g2o/core/optimization_algorithm_gauss_newton.h>
#include <g2o/core/optimization_algorithm_dogleg.h>
#include <g2o/solvers/dense/linear_solver_dense.h>
#include <Eigen/Core>
#include <opencv2/core/core.hpp>
#include <cmath>
#include <chrono>
using namespace std; 

// 曲线模型的顶点,模板参数:优化变量维度和数据类型
class CurveFittingVertex: public g2o::BaseVertex<3, Eigen::Vector3d>
{
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW
    virtual void setToOriginImpl() // 重置
    {
        _estimate << 0,0,0;
    }

    virtual void oplusImpl( const double* update ) // 更新
    {
        _estimate += Eigen::Vector3d(update);
    }
    // 存盘和读盘:留空
    virtual bool read( istream& in ) {}
    virtual bool write( ostream& out ) const {}
};

// 误差模型 模板参数:观测值维度,类型,连接顶点类型
class CurveFittingEdge: public g2o::BaseUnaryEdge<1,double,CurveFittingVertex>
{
public:
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW
    CurveFittingEdge( double x ): BaseUnaryEdge(), _x(x) {}
    // 计算曲线模型误差
    void computeError()
    {
        const CurveFittingVertex* v = static_cast<const CurveFittingVertex*> (_vertices[0]);
        const Eigen::Vector3d abc = v->estimate();
        _error(0,0) = _measurement - std::exp( abc(0,0)*_x*_x + abc(1,0)*_x + abc(2,0) ) ;
    }
    virtual bool read( istream& in ) {}
    virtual bool write( ostream& out ) const {}
public:
    double _x;  // x 值, y 值为 _measurement
};

int main( int argc, char** argv )
{
    double a=1.0, b=2.0, c=1.0;         // 真实参数值
    int N=100;                          // 数据点
    double w_sigma=1.0;                 // 噪声Sigma值
    cv::RNG rng;                        // OpenCV随机数产生器
    double abc[3] = {0,0,0};            // abc参数的估计值

    vector<double> x_data, y_data;      // 数据

    cout<<"generating data: "<<endl;
    for ( int i=0; i<N; i++ )
    {
        double x = i/100.0;
        x_data.push_back ( x );
        y_data.push_back (
            exp ( a*x*x + b*x + c ) + rng.gaussian ( w_sigma )
        );
        cout<<x_data[i]<<" "<<y_data[i]<<endl;
    }

    // 构建图优化,先设定g2o
    typedef g2o::BlockSolver< g2o::BlockSolverTraits<3,1> > Block;  // 每个误差项优化变量维度为3,误差值维度为1

    //-----修改以下注释到下行代码-----------//
    // Block::LinearSolverType* linearSolver = new g2o::LinearSolverDense<Block::PoseMatrixType>(); // 线性方程求解器
    std::unique_ptr<Block::LinearSolverType> linearSolver ( new g2o::LinearSolverDense<Block::PoseMatrixType>());

    //-----修改以下注释到下行代码-----------//
    //Block* solver_ptr = new Block( linearSolver );      // 矩阵块求解器
    std::unique_ptr<Block> solver_ptr ( new Block ( std::move(linearSolver)));

    // 梯度下降方法,从GN, LM, DogLeg 中选
    //-----修改以下注释到下行代码-----------//
    // g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( solver_ptr );
    g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( std::move(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 );       // 打开调试输出

    // 往图中增加顶点
    CurveFittingVertex* v = new CurveFittingVertex();
    v->setEstimate( Eigen::Vector3d(0,0,0) );
    v->setId(0);
    optimizer.addVertex( v );

    // 往图中增加边
    for ( int i=0; i<N; i++ )
    {
        CurveFittingEdge* edge = new CurveFittingEdge( x_data[i] );
        edge->setId(i);
        edge->setVertex( 0, v );                // 设置连接的顶点
        edge->setMeasurement( y_data[i] );      // 观测数值
        edge->setInformation( Eigen::Matrix<double,1,1>::Identity()*1/(w_sigma*w_sigma) ); // 信息矩阵:协方差矩阵之逆
        optimizer.addEdge( edge );
    }

    // 执行优化
    cout<<"start optimization"<<endl;
    chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
    optimizer.initializeOptimization();
    optimizer.optimize(100);
    chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
    chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>>( t2-t1 );
    cout<<"solve time cost = "<<time_used.count()<<" seconds. "<<endl;

    // 输出优化值
    Eigen::Vector3d abc_estimate = v->estimate();
    cout<<"estimated model: "<<abc_estimate.transpose()<<endl;

    return 0;
}
PretDB commented 6 years ago

@zhkmxx9302013 , I had also met this problem, thanks. You can make a pull request maybe.

zhkmxx9302013 commented 6 years ago

@PretDB Glad it works to you, but no need make a pull request, it's the problem of g2o version. ∩_∩

shanpenghui commented 4 years ago

It works! Thanks.