一、ORB-SLAM2专用库的编译
ORB-SLAM2使用的G2O库是在原始的库上进行了删减与修改,使之适用于ORB-SLAM2程序。
1.1、下载地址:https://github.com/raulmur/ORB_SLAM2/tree/master/Thirdparty/g2o
1.2、编译过程中仅需要配置eigen库即可,下载
1.3、其他库的配置方式和下面一致。
1.4、编译时出现错误:命令行 error D8021: 无效的数值参数“/Wno-deprecated-declarations”。解决方式参见这篇博客。
二、通用G2O库的编译
- 由于之前下载了最新版本的额g2o一直没有编译成功,所以下载了一个低版本的g2o,结果直接成功了,因此个人认为编译成功的重点在于版本一定要选择正确。
- 通用库存在一些问题,比如使用EdgeProjectXYZ2UVPoseOnly类时,会出现这个类里面的函数未定义的错误。原因是在源代码中,并未将这个类输出到lib中,因此找不到这个类里边的函数的定义。
- 解决方式可以是类似于SLAM14讲中第七讲的pose_estimation_3d3d.cpp或是第九讲的第三个工程代码里边的g2o_types.cpp所用的重新自定义该优化函数的方式。或是类似于ORB-SLAM2里边的G2O的方式,在类前面添加一个输出,将该类输出到lib中,这样就可以使用了。
具体的编译步骤为:
2.1、g2o-20170730的下载(2020版本的一直没有编译成功,,,)
https://github.com/RainerKuemmerle/g2o/tree/20170730_git
2.2、Eigen依赖库的下载(我用的是eigen3.2.10,版本不能太高,否则会报错,参见博客https://blog.csdn.net/weixin_40279988/article/details/88699083)
https://gitlab.com/libeigen/eigen/-/archive/3.2.10/eigen-3.2.10.zip
2.3、suitesparse库的下载与编译
这个以前用vs2017编译过,直接用cmake编译就可以了,用的是1.5.0版本:https://github.com/jlblancoc/suitesparse-metis-for-windows/tree/v1.5.0
2.4、g2o的编译
cmake版本使用的是3.9.3。
cmake配置完成之后应该需要包含以下:
Eigen和suitesparse
BLAS库
Cholmod库
安装路径可以修改如下
Csparse文件
Lapack库
按照以上配置完成后,直接打开工程编译安装即可。
2.5、代码使用示例
代码和数据可以参考:https://github.com/gaoxiang12/g2o_ba_example
可以通过工程属性配置或是新建属性页,各有优势。
包含目录:
D:\build\3rdparty\g2o_\g2o-20170730_git\install\include
D:\build\3rdparty\g2o_\dependency\suitesparse-1.5.0\install\include
D:\build\3rdparty\g2o_\dependency\suitesparse-1.5.0\install\include\suitespars
D:\build\3rdparty\g2o_\dependency\eigen-3.2.10
库目录:
D:\build\3rdparty\g2o_\dependency\suitesparse-1.5.0\install\lib
D:\build\3rdparty\g2o_\g2o-20170730_git\install\lib
链接器-输入:
D:\build\3rdparty\g2o_\g2o-20170730_git\install\lib\*.lib(如果是Debug版本:D:\build\3rdparty\g2o_\g2o-20170730_git\install\lib\*d.lib)
D:\build\3rdparty\g2o_\dependency\suitesparse-1.5.0\install\lib\*.lib
具体的路径需要自己修改。
注意:一定要将之前编译g2o过程中,D:\build\3rdparty\g2o_\dependency\suitesparse-1.5.0\lapack_windows\x64路径下(根据自己放置的库路径选择)用到的liblapack.lib和libblas.lib库添加到链接器-输入中。最简单的方式是直接将其复制到g2o安装的lib文件中。
工程属性-C/C++-预处理器需要添加:_WINDOWS
OpenCV就自己配置了,OpenCV3或4都可以。
关于dll文件,缺什么添什么,或是直接在工程属性-调试-环境下添加:path=D:\build\3rdparty\g2o_\g2o-20170730_git\install\bin;(一定注意最后的分号是必须的)
最后输出:
error = 2.93668
error = 1.76704
error = 1.49284
error = 1.21638
error = 2.26033
error = 52.0022
error = 1.04709
error = 1.02888
error = 1.17111
error = 4.14609
error = 33.7051
error = 4.09188
error = 10.2927
error = 1.15157
error = 2.89458
error = 2.93601
error = 1.07343
error = 16.7437
error = 13.3794
error = 1.51885
error = 3.53293
error = 4.42817
error = 1.32642
inliers in total points: 1294/1362
附代码(建议删除中文调试,因为可能出现乱码错误):
/**
* BA Example
* Author: Xiang Gao
* Date: 2016.3
* Email: gaoxiang12@mails.tsinghua.edu.cn
*
* 在这个程序中,我们读取两张图像,进行特征匹配。然后根据匹配得到的特征,计算相机运动以及特征点的位置。这是一个典型的Bundle Adjustment,我们用g2o进行优化。
*/
// for std
#include <iostream>
// for opencv
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
//#include <boost/concept_check.hpp>
// for g2o
#include <g2o/core/sparse_optimizer.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/robust_kernel.h>
#include <g2o/core/robust_kernel_impl.h>
#include <g2o/core/optimization_algorithm_levenberg.h>
#include <g2o/solvers/cholmod/linear_solver_cholmod.h>
#include <g2o/types/slam3d/se3quat.h>
#include <g2o/types/sba/types_six_dof_expmap.h>
int findCorrespondingPoints( const cv::Mat& img1, const cv::Mat& img2, std::vector<cv::Point2f>& points1, std::vector<cv::Point2f>& points2 );
double cx = 325.5;
double cy = 253.5;
double fx = 518.0;
double fy = 519.0;
int main( int argc, char** argv )
{
cv::Mat img1 = cv::imread("./data/1.png");
cv::Mat img2 = cv::imread("./data/2.png");
std::vector<cv::Point2f> pts1;
std::vector<cv::Point2f> pts2;
if ( findCorrespondingPoints( img1, img2, pts1, pts2 ) == false )
{
std::cout<<"no enough matches"<< std::endl;
return 0;
}
std::cout<<"found:"<<pts1.size()<<" matches"<< std::endl;
g2o::SparseOptimizer optimizer;
g2o::BlockSolver_6_3::LinearSolverType* linearSolver = new g2o::LinearSolverCholmod<g2o::BlockSolver_6_3::PoseMatrixType> ();
g2o::BlockSolver_6_3* block_solver = new g2o::BlockSolver_6_3( linearSolver );
g2o::OptimizationAlgorithmLevenberg* algorithm = new g2o::OptimizationAlgorithmLevenberg( block_solver );
optimizer.setAlgorithm( algorithm );
optimizer.setVerbose( false );
for ( int i=0; i<2; i++ )
{
g2o::VertexSE3Expmap* v = new g2o::VertexSE3Expmap();
v->setId(i);
if ( i == 0)
v->setFixed( true );
v->setEstimate( g2o::SE3Quat() );
optimizer.addVertex( v );
}
for ( size_t i=0; i<pts1.size(); i++ )
{
g2o::VertexSBAPointXYZ* v = new g2o::VertexSBAPointXYZ();
v->setId( 2 + i );
double z = 1;
double x = ( pts1[i].x - cx ) * z / fx;
double y = ( pts1[i].y - cy ) * z / fy;
v->setMarginalized(true);
v->setEstimate( Eigen::Vector3d(x,y,z) );
optimizer.addVertex( v );
}
g2o::CameraParameters* camera = new g2o::CameraParameters( fx, Eigen::Vector2d(cx, cy), 0 );
camera->setId(0);
optimizer.addParameter( camera );
std::vector<g2o::EdgeProjectXYZ2UV*> edges;
for ( size_t i=0; i<pts1.size(); i++ )
{
g2o::EdgeProjectXYZ2UV* edge = new g2o::EdgeProjectXYZ2UV();
edge->setVertex( 0, dynamic_cast<g2o::VertexSBAPointXYZ*> (optimizer.vertex(i+2)) );
edge->setVertex( 1, dynamic_cast<g2o::VertexSE3Expmap*> (optimizer.vertex(0)) );
edge->setMeasurement( Eigen::Vector2d(pts1[i].x, pts1[i].y ) );
edge->setInformation( Eigen::Matrix2d::Identity() );
edge->setParameterId(0, 0);
edge->setRobustKernel( new g2o::RobustKernelHuber() );
optimizer.addEdge( edge );
edges.push_back(edge);
}
for ( size_t i=0; i<pts2.size(); i++ )
{
g2o::EdgeProjectXYZ2UV* edge = new g2o::EdgeProjectXYZ2UV();
edge->setVertex( 0, dynamic_cast<g2o::VertexSBAPointXYZ*> (optimizer.vertex(i+2)) );
edge->setVertex( 1, dynamic_cast<g2o::VertexSE3Expmap*> (optimizer.vertex(1)) );
edge->setMeasurement( Eigen::Vector2d(pts2[i].x, pts2[i].y ) );
edge->setInformation( Eigen::Matrix2d::Identity() );
edge->setParameterId(0,0);
edge->setRobustKernel( new g2o::RobustKernelHuber() );
optimizer.addEdge( edge );
edges.push_back(edge);
}
std::cout<<"start optimizer"<< std::endl;
optimizer.setVerbose(true);
optimizer.initializeOptimization();
optimizer.optimize(10);
std::cout<<"finish optimizer"<< std::endl;
g2o::VertexSE3Expmap* v = dynamic_cast<g2o::VertexSE3Expmap*>( optimizer.vertex(1) );
Eigen::Isometry3d pose = v->estimate();
std::cout<<"Pose="<< std::endl<<pose.matrix()<< std::endl;
for ( size_t i=0; i<pts1.size(); i++ )
{
g2o::VertexSBAPointXYZ* v = dynamic_cast<g2o::VertexSBAPointXYZ*> (optimizer.vertex(i+2));
std::cout<<"vertex id "<<i+2<<", pos = ";
Eigen::Vector3d pos = v->estimate();
std::cout<<pos(0)<<","<<pos(1)<<","<<pos(2)<< std::endl;
}
int inliers = 0;
for ( auto e:edges )
{
e->computeError();
if ( e->chi2() > 1 )
{
std::cout<<"error = "<<e->chi2()<< std::endl;
}
else
{
inliers++;
}
}
std::cout<<"inliers in total points: "<<inliers<<"/"<<pts1.size()+pts2.size()<< std::endl;
optimizer.save("ba.g2o");
return 0;
}
int findCorrespondingPoints( const cv::Mat& img1, const cv::Mat& img2, std::vector<cv::Point2f>& points1, std::vector<cv::Point2f>& points2 )
{
cv::Ptr<cv::ORB> orb = cv::ORB::create(1000);
std::vector<cv::KeyPoint> kp1, kp2;
cv::Mat desp1, desp2;
orb->detectAndCompute( img1, cv::Mat(), kp1, desp1 );
orb->detectAndCompute( img2, cv::Mat(), kp2, desp2 );
cv::Ptr<cv::DescriptorMatcher> matcher = cv::DescriptorMatcher::create( "BruteForce-Hamming");
double knn_match_ratio=0.8;
std::vector< std::vector<cv::DMatch> > matches_knn;
matcher->knnMatch( desp1, desp2, matches_knn, 2 );
std::vector< cv::DMatch > matches;
for ( size_t i=0; i<matches_knn.size(); i++ )
{
if (matches_knn[i][0].distance < knn_match_ratio * matches_knn[i][1].distance )
matches.push_back( matches_knn[i][0] );
}
if (matches.size() <= 20)
return false;
for ( auto m:matches )
{
points1.push_back( kp1[m.queryIdx].pt );
points2.push_back( kp2[m.trainIdx].pt );
}
return true;
}
编译好的G2O:https://download.csdn.net/download/qq_38589460/15384979
参考博客:https://blog.csdn.net/yhz78321/article/details/79922592?utm_source=blogxgwz4
https://blog.csdn.net/weixin_40279988/article/details/88699083
https://blog.csdn.net/aptx704610875/article/details/51245143
https://blog.csdn.net/xiaopihai1993/article/details/76644656