/*源代码的运行过程发现出不来结果,无独有偶,发现网上也有很多大神出现过这种错误,改了之后是可以运行的,因此修改了一下高博士的部分代码,贴出来分享一下!*/
文件名:pose_estimation_3d2d.cpp 此处的错误是在ptr指针(线性方程求解器和矩阵块求解器)
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
using namespace cv;
void find_feature_matches (
const Mat& img_1, const Mat& img_2,
std::vector& keypoints_1,
std::vector& keypoints_2,
std::vector< DMatch >& matches );
// 像素坐标转相机归一化坐标
Point2d pixel2cam ( const Point2d& p, const Mat& K );
void bundleAdjustment (
const vector points_3d,
const vector points_2d,
const Mat& K,
Mat& R, Mat& t
);
int main ( int argc, char** argv )
{
if ( argc != 5 )
{
cout<<"usage: pose_estimation_3d2d img1 img2 depth1 depth2"< keypoints_1, keypoints_2;
vector matches;
find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches );
cout<<"一共找到了"< ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );
vector pts_3d;
vector pts_2d;
for ( DMatch m:matches )
{
ushort d = d1.ptr (int ( keypoints_1[m.queryIdx].pt.y )) [ int ( keypoints_1[m.queryIdx].pt.x ) ];
if ( d == 0 ) // bad depth
continue;
float dd = d/5000.0;
Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );
pts_3d.push_back ( Point3f ( p1.x*dd, p1.y*dd, dd ) );
pts_2d.push_back ( keypoints_2[m.trainIdx].pt );
}
cout<<"3d-2d pairs: "<& keypoints_1,
std::vector& keypoints_2,
std::vector< DMatch >& matches )
{
//-- 初始化
Mat descriptors_1, descriptors_2;
// used in OpenCV3
Ptr detector = ORB::create();
Ptr descriptor = ORB::create();
// use this if you are in OpenCV2
// Ptr detector = FeatureDetector::create ( "ORB" );
// Ptr descriptor = DescriptorExtractor::create ( "ORB" );
Ptr matcher = DescriptorMatcher::create ( "BruteForce-Hamming" );
//-- 第一步:检测 Oriented FAST 角点位置
detector->detect ( img_1,keypoints_1 );
detector->detect ( img_2,keypoints_2 );
//-- 第二步:根据角点位置计算 BRIEF 描述子
descriptor->compute ( img_1, keypoints_1, descriptors_1 );
descriptor->compute ( img_2, keypoints_2, descriptors_2 );
//-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
vector match;
// BFMatcher matcher ( NORM_HAMMING );
matcher->match ( descriptors_1, descriptors_2, match );
//-- 第四步:匹配点对筛选
double min_dist=10000, max_dist=0;
//找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离
for ( int i = 0; i < descriptors_1.rows; i++ )
{
double dist = match[i].distance;
if ( dist < min_dist ) min_dist = dist;
if ( dist > max_dist ) max_dist = dist;
}
printf ( "-- Max dist : %f \n", max_dist );
printf ( "-- Min dist : %f \n", min_dist );
//当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限.
for ( int i = 0; i < descriptors_1.rows; i++ )
{
if ( match[i].distance <= max ( 2*min_dist, 30.0 ) )
{
matches.push_back ( match[i] );
}
}
}
Point2d pixel2cam ( const Point2d& p, const Mat& K )
{
return Point2d
(
( p.x - K.at ( 0,2 ) ) / K.at ( 0,0 ),
( p.y - K.at ( 1,2 ) ) / K.at ( 1,1 )
);
}
void bundleAdjustment (
const vector< Point3f > points_3d,
const vector< Point2f > points_2d,
const Mat& K,
Mat& R, Mat& t )
{
// 初始化g2o
typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block; // pose 维度为 6, landmark 维度为 3
//Block::LinearSolverType* linearSolver = new g2o::LinearSolverCSparse(); // 线性方程求解器
std::unique_ptr linearSolver ( new g2o::LinearSolverCSparse());
//Block* solver_ptr = new Block ( linearSolver ); // 矩阵块求解器
std::unique_ptr solver_ptr ( new Block ( std::move(linearSolver))); // 矩阵块求解器
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( std::move(solver_ptr));
g2o::SparseOptimizer optimizer;
optimizer.setAlgorithm ( solver );
// vertex
g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); // camera pose
Eigen::Matrix3d R_mat;
R_mat <<
R.at ( 0,0 ), R.at ( 0,1 ), R.at ( 0,2 ),
R.at ( 1,0 ), R.at ( 1,1 ), R.at ( 1,2 ),
R.at ( 2,0 ), R.at ( 2,1 ), R.at ( 2,2 );
pose->setId ( 0 );
pose->setEstimate ( g2o::SE3Quat (
R_mat,
Eigen::Vector3d ( t.at ( 0,0 ), t.at ( 1,0 ), t.at ( 2,0 ) )
) );
optimizer.addVertex ( pose );
int index = 1;
for ( const Point3f p:points_3d ) // landmarks
{
g2o::VertexSBAPointXYZ* point = new g2o::VertexSBAPointXYZ();
point->setId ( index++ );
point->setEstimate ( Eigen::Vector3d ( p.x, p.y, p.z ) );
point->setMarginalized ( true ); // g2o 中必须设置 marg 参见第十讲内容
optimizer.addVertex ( point );
}
// parameter: camera intrinsics
g2o::CameraParameters* camera = new g2o::CameraParameters (
K.at ( 0,0 ), Eigen::Vector2d ( K.at ( 0,2 ), K.at ( 1,2 ) ), 0
);
camera->setId ( 0 );
optimizer.addParameter ( camera );
// edges
index = 1;
for ( const Point2f p:points_2d )
{
g2o::EdgeProjectXYZ2UV* edge = new g2o::EdgeProjectXYZ2UV();
edge->setId ( index );
edge->setVertex ( 0, dynamic_cast ( optimizer.vertex ( index ) ) );
edge->setVertex ( 1, pose );
edge->setMeasurement ( Eigen::Vector2d ( p.x, p.y ) );
edge->setParameterId ( 0,0 );
edge->setInformation ( Eigen::Matrix2d::Identity() );
optimizer.addEdge ( edge );
index++;
}
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
optimizer.setVerbose ( true );
optimizer.initializeOptimization();
optimizer.optimize ( 100 );
chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
chrono::duration time_used = chrono::duration_cast> ( t2-t1 );
cout<<"optimization costs time: "<estimate() ).matrix() <
文件名:pose_estimation_3d3d.cpp
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
using namespace std;
using namespace cv;
void find_feature_matches (
const Mat& img_1, const Mat& img_2,
std::vector& keypoints_1,
std::vector& keypoints_2,
std::vector< DMatch >& matches );
// 像素坐标转相机归一化坐标
Point2d pixel2cam ( const Point2d& p, const Mat& K );
void pose_estimation_3d3d (
const vector& pts1,
const vector& pts2,
Mat& R, Mat& t
);
void bundleAdjustment(
const vector& points_3d,
const vector& points_2d,
Mat& R, Mat& t
);
// g2o edge
class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3Expmap>
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
EdgeProjectXYZRGBDPoseOnly( const Eigen::Vector3d& point ) : _point(point) {}
virtual void computeError()
{
const g2o::VertexSE3Expmap* pose = static_cast ( _vertices[0] );
// measurement is p, point is p'
_error = _measurement - pose->estimate().map( _point );
}
virtual void linearizeOplus()
{
g2o::VertexSE3Expmap* pose = static_cast(_vertices[0]);
g2o::SE3Quat T(pose->estimate());
Eigen::Vector3d xyz_trans = T.map(_point);
double x = xyz_trans[0];
double y = xyz_trans[1];
double z = xyz_trans[2];
_jacobianOplusXi(0,0) = 0;
_jacobianOplusXi(0,1) = -z;
_jacobianOplusXi(0,2) = y;
_jacobianOplusXi(0,3) = -1;
_jacobianOplusXi(0,4) = 0;
_jacobianOplusXi(0,5) = 0;
_jacobianOplusXi(1,0) = z;
_jacobianOplusXi(1,1) = 0;
_jacobianOplusXi(1,2) = -x;
_jacobianOplusXi(1,3) = 0;
_jacobianOplusXi(1,4) = -1;
_jacobianOplusXi(1,5) = 0;
_jacobianOplusXi(2,0) = -y;
_jacobianOplusXi(2,1) = x;
_jacobianOplusXi(2,2) = 0;
_jacobianOplusXi(2,3) = 0;
_jacobianOplusXi(2,4) = 0;
_jacobianOplusXi(2,5) = -1;
}
bool read ( istream& in ) {}
bool write ( ostream& out ) const {}
protected:
Eigen::Vector3d _point;
};
int main ( int argc, char** argv )
{
if ( argc != 5 )
{
cout<<"usage: pose_estimation_3d3d img1 img2 depth1 depth2"< keypoints_1, keypoints_2;
vector matches;
find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches );
cout<<"一共找到了"< ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );
vector pts1, pts2;
for ( DMatch m:matches )
{
ushort d1 = depth1.ptr ( int ( keypoints_1[m.queryIdx].pt.y ) ) [ int ( keypoints_1[m.queryIdx].pt.x ) ];
ushort d2 = depth2.ptr ( int ( keypoints_2[m.trainIdx].pt.y ) ) [ int ( keypoints_2[m.trainIdx].pt.x ) ];
if ( d1==0 || d2==0 ) // bad depth
continue;
Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );
Point2d p2 = pixel2cam ( keypoints_2[m.trainIdx].pt, K );
float dd1 = float ( d1 ) /5000.0;
float dd2 = float ( d2 ) /5000.0;
pts1.push_back ( Point3f ( p1.x*dd1, p1.y*dd1, dd1 ) );
pts2.push_back ( Point3f ( p2.x*dd2, p2.y*dd2, dd2 ) );
}
cout<<"3d-3d pairs: "<(3,1)<& keypoints_1,
std::vector& keypoints_2,
std::vector< DMatch >& matches )
{
//-- 初始化
Mat descriptors_1, descriptors_2;
// used in OpenCV3
Ptr detector = ORB::create();
Ptr descriptor = ORB::create();
// use this if you are in OpenCV2
// Ptr detector = FeatureDetector::create ( "ORB" );
// Ptr descriptor = DescriptorExtractor::create ( "ORB" );
Ptr matcher = DescriptorMatcher::create("BruteForce-Hamming");
//-- 第一步:检测 Oriented FAST 角点位置
detector->detect ( img_1,keypoints_1 );
detector->detect ( img_2,keypoints_2 );
//-- 第二步:根据角点位置计算 BRIEF 描述子
descriptor->compute ( img_1, keypoints_1, descriptors_1 );
descriptor->compute ( img_2, keypoints_2, descriptors_2 );
//-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
vector match;
// BFMatcher matcher ( NORM_HAMMING );
matcher->match ( descriptors_1, descriptors_2, match );
//-- 第四步:匹配点对筛选
double min_dist=10000, max_dist=0;
//找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离
for ( int i = 0; i < descriptors_1.rows; i++ )
{
double dist = match[i].distance;
if ( dist < min_dist ) min_dist = dist;
if ( dist > max_dist ) max_dist = dist;
}
printf ( "-- Max dist : %f \n", max_dist );
printf ( "-- Min dist : %f \n", min_dist );
//当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限.
for ( int i = 0; i < descriptors_1.rows; i++ )
{
if ( match[i].distance <= max ( 2*min_dist, 30.0 ) )
{
matches.push_back ( match[i] );
}
}
}
Point2d pixel2cam ( const Point2d& p, const Mat& K )
{
return Point2d
(
( p.x - K.at ( 0,2 ) ) / K.at ( 0,0 ),
( p.y - K.at ( 1,2 ) ) / K.at ( 1,1 )
);
}
void pose_estimation_3d3d (
const vector& pts1,
const vector& pts2,
Mat& R, Mat& t
)
{
Point3f p1, p2; // center of mass
int N = pts1.size();
for ( int i=0; i q1 ( N ), q2 ( N ); // remove the center
for ( int i=0; i svd ( W, Eigen::ComputeFullU|Eigen::ComputeFullV );
Eigen::Matrix3d U = svd.matrixU();
Eigen::Matrix3d V = svd.matrixV();
cout<<"U="< ( 3,3 ) <<
R_ ( 0,0 ), R_ ( 0,1 ), R_ ( 0,2 ),
R_ ( 1,0 ), R_ ( 1,1 ), R_ ( 1,2 ),
R_ ( 2,0 ), R_ ( 2,1 ), R_ ( 2,2 )
);
t = ( Mat_ ( 3,1 ) << t_ ( 0,0 ), t_ ( 1,0 ), t_ ( 2,0 ) );
}
void bundleAdjustment (
const vector< Point3f >& pts1,
const vector< Point3f >& pts2,
Mat& R, Mat& t )
{
// 初始化g2o
typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block; // pose维度为 6, landmark 维度为 3
Block::LinearSolverType* linearSolver = new g2o::LinearSolverEigen(); // 线性方程求解器
Block* solver_ptr = new Block( std::unique_ptr(linearSolver)); // 矩阵块求解器
g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton(std::unique_ptr(solver_ptr));
g2o::SparseOptimizer optimizer;
optimizer.setAlgorithm( solver );
// vertex
g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); // camera pose
pose->setId(0);
pose->setEstimate( g2o::SE3Quat(
Eigen::Matrix3d::Identity(),
Eigen::Vector3d( 0,0,0 )
) );
optimizer.addVertex( pose );
// edges
int index = 1;
vector edges;
for ( size_t i=0; isetId( index );
edge->setVertex( 0, dynamic_cast (pose) );
edge->setMeasurement( Eigen::Vector3d(
pts1[i].x, pts1[i].y, pts1[i].z) );
edge->setInformation( Eigen::Matrix3d::Identity()*1e4 );
optimizer.addEdge(edge);
index++;
edges.push_back(edge);
}
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
optimizer.setVerbose( true );
optimizer.initializeOptimization();
optimizer.optimize(10);
chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
chrono::duration time_used = chrono::duration_cast>(t2-t1);
cout<<"optimization costs time: "<estimate() ).matrix()<
文件名:feature_extraction.cpp
#include
#include
#include
#include
using namespace std;
using namespace cv;
int main(int argc, char** argv)
{
if(argc!=3)//判断命令行输入对错
{
cout<<"usage: feature_extraction img1 img2"< keypoints_1, keypoints_2;
//创建两张图像的描述子,类型是Mat类型
Mat descriptors_1, descriptors_2;
//创建一个ORB类型指针orb,ORB类是继承自Feature2D类
//class CV_EXPORTS_W ORB : public Feature2D
//这里看一下create()源码:参数较多,不介绍。
//creat()方法所有参数都有默认值,返回static Ptr类型。
/*
CV_WRAP static Ptr create(int nfeatures=500,
float scaleFactor=1.2f,
int nlevels=8,
int edgeThreshold=31,
int firstLevel=0,
int WTA_K=2,
int scoreType=ORB::HARRIS_SCORE,
int patchSize=31,
int fastThreshold=20);
*/
//所以这里的语句就是创建一个Ptr类型的orb,用于接收ORB类中create()函数的返回值
Ptr orb = ORB::create();
//第一步:检测Oriented FAST角点位置.
//detect是Feature2D中的方法,orb是子类指针,可以调用
//看一下detect()方法的原型参数:需要检测的图像,关键点数组,第三个参数为默认值
/*
CV_WRAP virtual void detect( InputArray image,
CV_OUT std::vector& keypoints,
InputArray mask=noArray() );
*/
orb->detect(img_1, keypoints_1);
orb->detect(img_2, keypoints_2);
//第二步:根据角点位置计算BRIEF描述子
//compute是Feature2D中的方法,orb是子类指针,可以调用
//看一下compute()原型参数:图像,图像的关键点数组,Mat类型的描述子
/*
CV_WRAP virtual void compute( InputArray image,
CV_OUT CV_IN_OUT std::vector& keypoints,
OutputArray descriptors );
*/
orb->compute(img_1, keypoints_1, descriptors_1);
orb->compute(img_2, keypoints_2, descriptors_2);
//定义输出检测特征点的图片。
Mat outimg1;
//drawKeypoints()函数原型参数:原图,原图关键点,带有关键点的输出图像,后面两个为默认值
/*
CV_EXPORTS_W void drawKeypoints( InputArray image,
const std::vector& keypoints,
InputOutputArray outImage,
const Scalar& color=Scalar::all(-1),
int flags=DrawMatchesFlags::DEFAULT );
*/
//注意看,这里并没有用到描述子,描述子的作用是用于后面的关键点筛选。
drawKeypoints(img_1, keypoints_1, outimg1, Scalar::all(-1), DrawMatchesFlags::DEFAULT);
imshow("ORB detectors",outimg1);
//第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
//创建一个匹配点数组,用于承接匹配出的DMatch,其实叫match_points_array更为贴切。matches类型为数组,元素类型为DMatch
vector matches;
//创建一个BFMatcher匹配器,BFMatcher类构造函数如下:两个参数都有默认值,但是第一个距离类型下面使用的并不是默认值,而是汉明距离
//CV_WRAP BFMatcher( int normType=NORM_L2, bool crossCheck=false );
BFMatcher matcher (NORM_HAMMING);
//调用matcher的match方法进行匹配,这里用到了描述子,没有用关键点。
//匹配出来的结果写入上方定义的matches[]数组中
matcher.match(descriptors_1, descriptors_2, matches);
//第四步:遍历matches[]数组,找出匹配点的最大距离和最小距离,用于后面的匹配点筛选。
//这里的距离是上方求出的汉明距离数组,汉明距离表征了两个匹配的相似程度,所以也就找出了最相似和最不相似的两组点之间的距离。
double min_dist=0, max_dist=0;//定义距离
for (int i = 0; i < descriptors_1.rows; ++i)//遍历
{
double dist = matches[i].distance;
if(distmax_dist) max_dist = dist;
}
printf("Max dist: %f\n", max_dist);
printf("Min dist: %f\n", min_dist);
//第五步:根据最小距离,对匹配点进行筛选,
//当描述自之间的距离大于两倍的min_dist,即认为匹配有误,舍弃掉。
//但是有时最小距离非常小,比如趋近于0了,所以这样就会导致min_dist到2*min_dist之间没有几个匹配。
// 所以,在2*min_dist小于30的时候,就取30当上限值,小于30即可,不用2*min_dist这个值了
std::vector good_matches;
for (int j = 0; j < descriptors_1.rows; ++j)
{
if (matches[j].distance <= max(2*min_dist, 30.0))
good_matches.push_back(matches[j]);
}
//第六步:绘制匹配结果
Mat img_match;//所有匹配点图
//这里看一下drawMatches()原型参数,简单用法就是:图1,图1关键点,图2,图2关键点,匹配数组,承接图像,后面的有默认值
/*
CV_EXPORTS_W void drawMatches( InputArray img1,
const std::vector& keypoints1,
InputArray img2,
const std::vector& keypoints2,
const std::vector& matches1to2,
InputOutputArray outImg,
const Scalar& matchColor=Scalar::all(-1),
const Scalar& singlePointColor=Scalar::all(-1),
const std::vector& matchesMask=std::vector(),
int flags=DrawMatchesFlags::DEFAULT );
*/
drawMatches(img_1, keypoints_1, img_2, keypoints_2, matches, img_match);
imshow("all th matches", img_match);
Mat img_goodmatch;//筛选后的匹配点图
drawMatches(img_1, keypoints_1, img_2, keypoints_2, good_matches, img_goodmatch);
imshow("matches", img_goodmatch);
waitKey(0);
return 0;
}
最后附两张结果图!加油!!