前言
BoW3和FBow是常用的词袋模型的开源算法。Bow(bag-of-words)也就是词袋,它的出发点是用几个特征表述一幅图像,其示意如图。在图像检索的过程中,将特征出现的次数进行统计(统计直方图 ),然后生成特征向量,经过分类器检索图片。在实际中,我们使用词袋的目的是为了加快图片检索的速度。其主要用于slam算法中的回环检测。 Bow3原理讲解,词袋模型在SLAM算法中的应用,视觉SLAM十四讲中也用对此的原理讲解。 本文主要说明了BoW3和FBow算法的使用与新能对比。
1.BoW3
ORB-SLAM2中用到的词袋模型算法是BoW2,Bow3是它升级版本,它的升级是减少了依赖库,只依赖opencv,具体区别为;
- DBoW3依赖项只有OpenCV,DBoW2依赖项DLIB被移除。
- DBoW3可以直接使用二值和浮点特征描述子,不需要再为这些特征描述子重写新类。
- DBoW3可以在Linux和Windows下编译。
- 为了优化执行速度,重写了部分代码(特征的操作都写入类DescManip);DBoW3的接口也被简化了。
- 可以使用二进制视觉词典文件;二进制文件在加载和保存上比.yml文件快4-5倍;而且,二进制文件还能被压缩。
- 仍然和DBoW2yml文件兼容。
1.1安装
源码地址,其本身是一个cmake的工程,使用cmake的安装方式即可。
mkdir build
cd build
cmake ..
make
sudo make install
注:DBoW3依赖opencv,使用前请查看opencv版本。
pkg-config --modversion opencv
本机版本:3.4.14。
1.2使用
这个库的说明文档写的很简单,使用这个库时,建议自己写脚本,这里在视觉SLAM十四讲ch12中的代码上修改,得到测试脚本。 cmakelist的编写
cmake_minimum_required( VERSION 2.8 )
project( loop_closure )
set( CMAKE_BUILD_TYPE "Release" )
set( CMAKE_CXX_FLAGS "-std=c++11 -O3" )
find_package( OpenCV 3.1 REQUIRED )
include_directories( ${OpenCV_INCLUDE_DIRS} )
set( DBoW3_INCLUDE_DIRS "/usr/local/include" )
set( DBoW3_LIBS "/usr/local/lib/libDBoW3.so" )
add_executable( feature_training feature_training.cpp )
target_link_libraries( feature_training ${OpenCV_LIBS} ${DBoW3_LIBS} )
add_executable( loop_closure loop_closure.cpp )
target_link_libraries( loop_closure ${OpenCV_LIBS} ${DBoW3_LIBS} )
词袋训练代码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;
int main( int argc, char** argv )
{
cout<<"reading images... "<<endl;
vector<Mat> images;
for ( int i=0; i<35; i++ )
{
string path = "./test/"+to_string(i+1)+".jpg";
images.push_back( imread(path) );
}
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 );
}
cout<<"creating vocabulary ... "<<endl;
DBoW3::Vocabulary vocab;
vocab.create( descriptors );
cout<<"vocabulary info: "<<vocab<<endl;
vocab.save( "vocabulary.yml.gz" );
cout<<"done"<<endl;
return 0;
}
图片匹配代码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 )
{
cout<<"reading database"<<endl;
DBoW3::Vocabulary vocab("./vocabulary.yml.gz");
if ( vocab.empty() )
{
cerr<<"Vocabulary does not exist."<<endl;
return 1;
}
cout<<"reading images... "<<endl;
vector<Mat> images;
for ( int i=0; i<35; i++ )
{
string path = "./ex/"+to_string(i+1)+".jpg";
images.push_back(imread(path));
}
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 );
}
cout<<"comparing images with images "<<endl;
DBoW3::BowVector v1;
vocab.transform( descriptors[1], v1 );
for ( int j=0; j<images.size(); j++ )
{
DBoW3::BowVector v2;
vocab.transform( descriptors[j], v2 );
double score = vocab.score(v1, v2);
cout<<"image 2 "<<" vs image "<<(j+1)<<" : "<<score<<endl;
}
cout<<endl;
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;
db.query( descriptors[i], ret, 4);
cout<<"searching for image "<<i<<" returns "<<ret<<endl<<endl;
}
cout<<"done."<<endl;
}
2.FBoW
FBOW(Fast Bag of Words)是 DBow2/DBow3 库的极端优化版本,其加速了词袋的创建速度。
2.1安装
源码地址,安装方法和1.1一致。
mkdir build
cd build
cmake ..
make
sudo make install
2.2 使用
这里建立了与1.2相同名字的测试程序。 cmakelist的编写
cmake_minimum_required( VERSION 2.8 )
project( loop_closure )
set( CMAKE_BUILD_TYPE "Release" )
set( CMAKE_CXX_FLAGS "-std=c++11 -O3" )
find_package( OpenCV 3.1 REQUIRED )
include_directories( ${OpenCV_INCLUDE_DIRS} )
set( FBOW_INCLUDE_DIRS "/usr/local/include" )
set( FBOW_LIBS "/usr/local/lib/libfbow.so" )
add_executable( feature_training feature_training.cpp )
target_link_libraries( feature_training ${OpenCV_LIBS} ${FBOW_LIBS} )
add_executable( loop_closure loop_closure.cpp )
target_link_libraries( loop_closure ${OpenCV_LIBS} ${FBOW_LIBS} )
词袋训练代码feature_training.cpp
#include "fbow/fbow.h"
#include "fbow/vocabulary_creator.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 )
{
cout<<"reading images... "<<endl;
vector<Mat> images;
for ( int i=0; i<35; i++ )
{
string path = "./test/"+to_string(i+1)+".jpg";
images.push_back( imread(path) );
}
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 );
}
fbow::VocabularyCreator::Params params;
params.k = 10;
params.L = 5;
params.nthreads=1;
params.maxIters=0;
fbow::VocabularyCreator vocabCat;
cout<<"creating vocabulary ... "<<endl;
fbow::Vocabulary vocab;
vocabCat.create(vocab,descriptors,"hf-net",params);
vocab.saveToFile("filename");
cout<<"done"<<endl;
return 0;
}
图片匹配代码loop_closure.cpp。
#include "fbow/fbow.h"
#include "fbow/vocabulary_creator.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 )
{
cout<<"reading database"<<endl;
fbow::Vocabulary vocab;
vocab.readFromFile("filename");
if (vocab.isValid() == 0)
{
cerr<<"Vocabulary does not exist."<<endl;
return 1;
}
cout<<"reading images... "<<endl;
vector<Mat> images;
for ( int i=0; i<35; i++ )
{
string path = "./ex/"+to_string(i+1)+".jpg";
images.push_back(imread(path));
}
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 );
}
cout<<"comparing images with images "<<endl;
fbow::fBow bowvector1;
bowvector1 = vocab.transform(descriptors[1]);
for ( int j=0; j<images.size(); j++ )
{
fbow::fBow bowvector2;
bowvector2 = vocab.transform(descriptors[j]);
double score = fbow::fBow::score(bowvector1,bowvector2);
cout<<"image 2 "<<" vs image "<<(j+1)<<" : "<<score<<endl;
}
cout<<endl;
cout<<"done."<<endl;
}
3.性能比较
运行程序的指令都为:
build/feature_training
build/loop_closure
测试运行时间,这里使用time命令进行测试: 词袋生成程序运行时间
| BOW3 | FBOW |
---|
real | 1.297s | 0.474s | user(执行时间) | 1.634s | 0.799s | sys | 0.091s | 0.097s |
图片检索程序运行时间
| BOW3 | FBOW |
---|
real | 0.531s | 0.508s | user(执行时间) | 0.871s | 0.777s | sys | 0.090s | 0.117s |
注:FBOW的优势主要在词袋的生成上,但它的依赖库比较多。 图片匹配测试:
| 1 | 2 | 3 | 4 | 5 | 6 | 26 | 27 | 28 | 29 | 30 | 31 | 32 |
---|
BOW3 | 0.076 | 1.000 | 0.083 | 0.040 | 0.040 | 0.014 | 0.021 | 0.011 | 0.007 | 0.006 | 0.012 | 0.004 | 0.003 | FBOW | 0.175 | 0.999 | 0.214 | 0.198 | 0.172 | 0.196 | 0.190 | 0.200 | 0.029 | 0.072 | 0.043 | 0.053 | 0.108 |
**注:数字为图片编号,以上测试数据是在利用词袋的情况下,图片2(目标图片)**与剩下的图片一一匹配的结果。BOW3与不一样的图片匹配得分偏低。
|