12章有三块程序,首先是创建字典feature_training.cpp
#include "DBoW3/DBoW3.h"
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <iostream>
#include <vector>
#include <string>
using namespace cv;
using namespace std;
/***************************************************
* 本节演示了如何根据data/目录下的十张图训练字典
* ************************************************/
int main( int argc, char** argv )
{
// read the image
cout<<"reading images... "<<endl;
vector<Mat> images;
for ( int i=0; i<10; i++ )
{
string path = "./data/"+to_string(i+1)+".png";
images.push_back( imread(path) );
}
// detect ORB features
cout<<"detecting ORB features ... "<<endl;
Ptr< Feature2D > detector = ORB::create();
vector<Mat> descriptors;
for ( Mat& image:images )
{
vector<KeyPoint> keypoints;
Mat descriptor;
detector->detectAndCompute( image, Mat(), keypoints, descriptor );
descriptors.push_back( descriptor );
}
// create vocabulary
cout<<"creating vocabulary ... "<<endl;
//简单易用,创建一个字典对象
DBoW3::Vocabulary vocab;
//调用create()函数,并用上方检测出来的描述子数组创建
vocab.create( descriptors );
cout<<"vocabulary info: "<<vocab<<endl;
//save()函数输出字典压缩包,格式为vocabulary.yml.gz
vocab.save( "vocabulary.yml.gz" );
cout<<"done"<<endl;
return 0;
}
用法很简单,创建字典对象,create()进数据,然后输出为.yml.gz文件即可。
loop_closure.cpp
#include "DBoW3/DBoW3.h"
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <iostream>
#include <vector>
#include <string>
using namespace cv;
using namespace std;
/***************************************************
* 本节演示了如何根据前面训练的字典计算相似性评分
* ************************************************/
int main( int argc, char** argv )
{
// read the images and database
cout<<"reading database"<<endl;
DBoW3::Vocabulary vocab("./vocabulary.yml.gz");
// DBoW3::Vocabulary vocab("./vocab_larger.yml.gz"); // use large vocab if you want:
if ( vocab.empty() )
{
cerr<<"Vocabulary does not exist."<<endl;
return 1;
}
cout<<"reading images... "<<endl;
vector<Mat> images;
for ( int i=0; i<10; i++ )
{
string path = "./data/"+to_string(i+1)+".png";
images.push_back( imread(path) );
}
// NOTE: in this case we are comparing images with a vocabulary generated by themselves, this may leed to overfitting.
// detect ORB features
cout<<"detecting ORB features ... "<<endl;
Ptr< Feature2D > detector = ORB::create();
vector<Mat> descriptors;
for ( Mat& image:images )
{
vector<KeyPoint> keypoints;
Mat descriptor;
detector->detectAndCompute( image, Mat(), keypoints, descriptor );
descriptors.push_back( descriptor );
}
// we can compare the images directly or we can compare one image to a database
// images :
cout<<"comparing images with images "<<endl;
for ( int i=0; i<images.size(); i++ )
{
//创建一个词袋描述向量,用于描述图像
DBoW3::BowVector v1;
/**
* 先看一下函数定义:
* virtual void transform(const cv::Mat & features, BowVector &v)
* 其实就是将图像转化成描述向量,用于相似性比较,v1为承接向量
*/
vocab.transform( descriptors[i], v1 );
//由于双向比较所以用了双循环,也就是image1与image10相似性和image10与image1相似性为两个比较。
for ( int j=i; j<images.size(); j++ )
{
//同样的方法取得另外一张图的描述向量,可以看出,由于j从=i开始,所以会比较到自身
DBoW3::BowVector v2;
vocab.transform( descriptors[j], v2 );
//核心功能,score()函数,传入两个词袋描述向量,然后取得相似性得分
double score = vocab.score(v1, v2);
cout<<"image "<<i<<" vs image "<<j<<" : "<<score<<endl;
}
cout<<endl;
}
/**
* 图像与图像之间的检测比较简单:
* 根据图像的描述子,调用transform()函数将图像转化成描述向量,
* 根据描述向量,调用score()函数求两张图像相似性得分。
*/
// or with database
cout<<"comparing images with database "<<endl;
//用字典创建一个基础数据集
DBoW3::Database db( vocab, false, 0);
//加入所有需要匹配的图像描述子
for ( int i=0; i<descriptors.size(); i++ )
db.add(descriptors[i]);
cout<<"database info: "<<db<<endl;
//输出匹配结果
for ( int i=0; i<descriptors.size(); i++ )
{
//创建一个结果队列对象,用于承接匹配结果
DBoW3::QueryResults ret;
//利用数据集的query()函数输出每一张图,以数据集为匹配依据,与输入的所有图像去匹配时的相似性结果,参数设置为输出最相似的四个。
db.query( descriptors[i], ret, 4); // max result=4
cout<<"searching for image "<<i<<" returns "<<ret<<endl<<endl;
}
cout<<"done."<<endl;
}
/**
* 与数据集匹配时一次性可以匹配到所有的图像匹配结果,并能够排序输出,
* 做法就是:
* 1、用字典创建一个数据集: DBoW3::Database db( vocab, false, 0)
* 2、把图像全都add()进去: db.add(descriptors[i]);
* 3、利用query()函数输出各个图的匹配结果: db.query( descriptors[i], ret, 4);
*/
后面还有个产生更多更大词典的gen_vocab_large.cpp
没什么新的,只是多读入了很多图,然后创建了更大的描述子数组,左后的生成词典的过程没有一点变化。
#include "DBoW3/DBoW3.h"
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <iostream>
#include <vector>
#include <string>
using namespace cv;
using namespace std;
int main( int argc, char** argv )
{
string dataset_dir = argv[1];
ifstream fin ( dataset_dir+"/associate.txt" );
if ( !fin )
{
cout<<"please generate the associate file called associate.txt!"<<endl;
return 1;
}
vector<string> rgb_files, depth_files;
vector<double> rgb_times, depth_times;
while ( !fin.eof() )
{
string rgb_time, rgb_file, depth_time, depth_file;
fin>>rgb_time>>rgb_file>>depth_time>>depth_file;
rgb_times.push_back ( atof ( rgb_time.c_str() ) );
depth_times.push_back ( atof ( depth_time.c_str() ) );
rgb_files.push_back ( dataset_dir+"/"+rgb_file );
depth_files.push_back ( dataset_dir+"/"+depth_file );
if ( fin.good() == false )
break;
}
fin.close();
cout<<"generating features ... "<<endl;
vector<Mat> descriptors;
Ptr< Feature2D > detector = ORB::create();
int index = 1;
for ( string rgb_file:rgb_files )
{
Mat image = imread(rgb_file);
vector<KeyPoint> keypoints;
Mat descriptor;
detector->detectAndCompute( image, Mat(), keypoints, descriptor );
descriptors.push_back( descriptor );
cout<<"extracting features from image " << index++ <<endl;
}
cout<<"extract total "<<descriptors.size()*500<<" features."<<endl;
// create vocabulary
cout<<"creating vocabulary, please wait ... "<<endl;
DBoW3::Vocabulary vocab;
vocab.create( descriptors );
cout<<"vocabulary info: "<<vocab<<endl;
vocab.save( "vocab_larger.yml.gz" );
cout<<"done"<<endl;
return 0;
}