实验设计 | 创建字典

本文提供两种格式词典的生成方法:

  1. yml格式
  2. txt格式

本文的目的是生成自己的词典,与ORB_SLAM2默认词典效果做对比。ORB_SLAM2使用的是txt格式,因此重点是生成txt格式的词典。只讲解词典的生成方法,不讲解理论知识。针对理论部分可以参考文章的参考blog,或自行查找。

1 yml格式

使用DBoW3生成yml格式的词典,在《视觉slam14讲》有详细的介绍。代码部分参考14讲

1.1 配置DBoW3库

  1. 源码下载:https://github.com/rmsalinas/DBoW3
  2. 编译安装

1.2 代码展示

  1. 字典生成代码
#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>

#include <ros/ros.h>

using namespace cv;
using namespace std;

/***************************************************
 * 本节演示了如何根据data/目录下的十张图训练字典
 * ************************************************/

int main( int argc, char** argv )
{
	ros::init(argc,argv,"createDBoW3_node");
	ros::NodeHandle n;
	
	//--step[1]: read the image 
	cout<<endl<<"step[1]:Load images ..."<<endl;
	vector<Mat> vmImgs;
	string sPath="/home/tdt/catkin_ws/src/RoboRTS/orb_slam2/data/";
	for(int i=0;i<10;i++)
	{
		string sImgPath=sPath + to_string(i)+".png";
		vmImgs.push_back(imread(sImgPath));
	}
	
	//--step[2]: detect ORB features
	cout<<endl<<"step[2]: detect ORB features ..."<<endl;
	Ptr<Feature2D> pfDetector=ORB::create(); 
	vector<KeyPoint> vkPoints;
	vector<Mat> vmdescriptors;
	for(Mat& img:vmImgs)
	{
		Mat descriptor;
		pfDetector->detectAndCompute(img,Mat(),vkPoints,descriptor);
		vmdescriptors.push_back(descriptor);
	}
	
	//--step[3]: create vocabulary 
	cout<<endl<<"step[3]: create vocabulary ..."<<endl;
	DBoW3::Vocabulary Voc;
	Voc.create(vmdescriptors);
	cout<<endl<<"Voc info: "<<Voc<<endl;
	Voc.save("vocabulary.yml.gz");
	cout<<endl<<"done"<<endl;
  return 0;
}
  1. 字典使用代码
#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>
// ROS
#include<ros/ros.h>

using namespace std ;
using namespace cv;

/***************************************************
 * 使用DBoW3
 * 本节演示了如何根据前面训练的字典计算相似性评分
 * ************************************************/
int main( int argc, char** argv )
{
	ros::init(argc,argv,"loadDBoW");
	ros::NodeHandle n;
	//--[1]: read the images and database  
	cout<<"reading database"<<endl;
	DBoW3::Vocabulary vocab("/home/tdt/catkin_ws/vocabulary.yml.gz");  // use large vocab if you want: 
	if ( vocab.empty() )
	{
		cerr<<"Vocabulary does not exist."<<endl;
		return 1;
	}
	//-- [2]: read images 
	cout<<"reading images... "<<endl;
	vector<Mat> images; 
	for ( int i=0; i<10; i++ )
	{
		string path = "/home/tdt/catkin_ws/src/RoboRTS/orb_slam2/data/"+to_string(i+1)+".png";
		images.push_back( imread(path) );
		imshow("tmpImg",images[i]);
		waitKey(100);
	}
	if(images.empty())
	{
		cout<<"images does not exist."<<endl;
	}
	//--[3]: 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 
	//	方法1: images 图像之间的比较
	cout<<"comparing images with images "<<endl;
	for ( int i=0; i<images.size(); i++ )
	{
		DBoW3::BowVector v1;
		vocab.transform( descriptors[i], v1 );
		for ( int j=i; j<images.size(); j++ )
		{
			DBoW3::BowVector v2;
			vocab.transform( descriptors[j], v2 );
			double score = vocab.score(v1, v2);
			cout<<"image "<<i<<" vs image "<<j<<" : "<<score<<endl;
		}
		cout<<endl;
	}
#endif 
	//	方法2: 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;
		db.query( descriptors[i], ret, 4);      // max result=4
		cout<<"searching for image "<<i<<" returns "<<ret<<endl<<endl;
	}
	cout<<"done."<<endl;
	return 0;
}
  1. CMakelists.txt 添加以下三处,CMakelists.txt 原始内容参考:实验设计 | ORB_SALM2写成RoboRTS下的一个功能包
// 添加1 
# dbow3 
# dbow3 is a simple lib so I assume you installed it in default directory 
set( DBoW3_INCLUDE_DIRS "/usr/local/include" )
set( DBoW3_LIBS "/usr/local/lib/libDBoW3.a" )
//添加2
add_executable( createDBoW3_node node/createDBoW3_node.cpp )
target_link_libraries( createDBoW3_node ${catkin_LIBRARIES} ${OpenCV_LIBS} ${DBoW3_LIBS} )
//添加3
add_executable( loadDBoW3_node node/loadDBoW3_node.cpp )
target_link_libraries( loadDBoW3_node ${catkin_LIBRARIES} ${OpenCV_LIBS} ${DBoW3_LIBS} )

2 txt格式

txt格式生成相对复杂,使用的是ORB_SLAM2/Thirdparty 中的DBoW2第三方库。ORB_SLAM2对该库进行了一定的删减,因此需要添加需要的文件。简单说明,具体流程如下:

2.1 添加文件到DBoW2

  1. 下载完整的DBoW2库:https://github.com/dorian3d/DBoW2
  2. 复制 TemplatedDatabase.h到…/Thirdparty/DBoW2/DBoW2
  3. 修改DBoW2的CMakeLists.txt
set(DBoW2/TemplatedDatabase.h  )
  1. 重新编译DBoW2

node:注意这里所说的DBoW2 是ORB_SLAM2第三方库中的
参考blog:

2.2 修改 ORBVocabulary.h

在…/ORB_SLAM2/include/ORBVocabulary.h 文件中添加如下内容:

typedef DBoW2::TemplatedDatabase<DBoW2::FORB::TDescriptor, DBoW2::FORB> ORBDatabase;

2.3 代码部分

  1. 字典生成代码
#include <iostream>
#include <algorithm>
#include <vector>
#include <string>
#include <opencv2/opencv.hpp>
// ROS
#include<ros/ros.h>
// DBoW2
#include "Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h"
#include "Thirdparty/DBoW2/DBoW2/TemplatedDatabase.h"
#include "Thirdparty/DBoW2/DBoW2/QueryResults.h"
#include "Thirdparty/DBoW2/DBoW2/BowVector.h"
#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
// ORB_SLAM2
#include "../include/ORBVocabulary.h"

using namespace std;
using namespace cv;

void LoadImages(const string   & strFile,
				vector<string> & vstrImageFileNames)
{
	ifstream f;
	f.open(strFile.c_str());
	while(!f.eof())
	{
		string str;
		getline(f,str);
		if(!str.empty());
		{
			stringstream ss;
			ss<<str;
			string sRGB;
			ss>>sRGB;
			if(!sRGB.empty())
			{
				cout<<sRGB<<endl;
				vstrImageFileNames.push_back(sRGB);
			}	
		}
	}
}

void changeStructure(const Mat &srcImg,vector<Mat> &stdImg)
{
	stdImg.resize(srcImg.rows);
	for(int i=0;i<srcImg.rows;i++)
	{
		stdImg[i]=srcImg.row(i);
	}
}

int main(int argc,char** argv)
{
	ros::init(argc,argv,"create_dbow_node");
	ros::NodeHandle n;
	//--step[1] 加载图像
	vector<string> vstrImageFileNames;	//!! 图像路径
	vector<Mat> vmImgs;					//!! 图像存储
	Mat mImg;							//!! 临时变量
	string dataPath="/home/tdt/catkin_ws/src/RoboRTS/orb_slam2/data";
	string strFile_01=string(dataPath+"/rgb.txt");
	LoadImages(strFile_01,vstrImageFileNames);
	int nImages=vstrImageFileNames.size();
	cout<<"images size: "<<nImages<<endl;
	for(int i=0;i<nImages;i++)
	{
		string sImgPath=string(dataPath+"/"+vstrImageFileNames[i]);
		cout<<sImgPath<<endl;
		mImg=imread(sImgPath,CV_LOAD_IMAGE_UNCHANGED);
		if(mImg.empty())
		{
			std::cerr<<endl<<"Failed to load image at:"<<string(dataPath)<<"/"<<vstrImageFileNames[i]<<endl;
			return -1;
		}
		vmImgs.push_back(mImg);
	}
	
	//--step[2] 计算描述子
	Ptr<ORB> orb=ORB::create(1000,1.2,8,31,0,2,ORB::FAST_SCORE);
	cout<<"Extracting ORB features ..."<<endl;
	vector<vector<Mat>>vmFeatures;
	for(int i=0;i<vmImgs.size();i++)
	{
		Mat mask;
		vector<KeyPoint> vKeyPoints;
		Mat mDescriptors;
		orb->detectAndCompute(vmImgs[i],mask,vKeyPoints,mDescriptors);
		vmFeatures.push_back(vector<Mat>());
		changeStructure(mDescriptors,vmFeatures.back());
	}

	//--step[3] 创建字典
	const int K=10;
	const int L=5;
	ORB_SLAM2::ORBVocabulary voc(K,L,DBoW2::TF_IDF,DBoW2::L1_NORM);
	voc.create(vmFeatures);
	voc.save("myVocabulary.yml.gz");
	voc.saveToTextFile("myVocabulary.txt"); 
	return 0;
}
  1. 字典使用代码
#include <iostream>
#include <algorithm>
#include <vector>
#include <string>
#include <opencv2/opencv.hpp>
// ROS
#include<ros/ros.h>
// DBoW2
#include "Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h"
#include "Thirdparty/DBoW2/DBoW2/TemplatedDatabase.h"
#include "Thirdparty/DBoW2/DBoW2/QueryResults.h"
#include "Thirdparty/DBoW2/DBoW2/BowVector.h"
#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
// ORB_SLAM2
#include "../include/ORBVocabulary.h"

using namespace std;
using namespace cv;

void changeStructure(const Mat &srcImg,vector<Mat> &stdImg)
{
	stdImg.resize(srcImg.rows);
	for(int i=0;i<srcImg.rows;i++)
	{
		stdImg[i]=srcImg.row(i);
	}
}

int main(int argc,char** argv)
{
	ros::init(argc,argv,"loadDBoW2_node");
	ros::NodeHandle n;
 	//--step[1]: read the database  
	cout<<endl<<"step[1]: Loading ORB Vocabulary. This could take a while... "<<endl;
	ORB_SLAM2::ORBVocabulary vocab;
	vocab.loadFromTextFile("/home/tdt/catkin_ws/src/RoboRTS/orb_slam2/Vocabulary/myVocabulary.txt");
	if ( vocab.empty() )
	{
		cerr<<"Vocabulary does not exist."<<endl;
		return 1;
	}
	//--step[2]: read images 
	cout<<endl<<"step[2]: reading images... "<<endl;
	vector<Mat> images; 
	for ( int i=0; i<10; i++ )
	{
		string path = "/home/tdt/catkin_ws/src/RoboRTS/orb_slam2/data/"+to_string(i+1)+".png";
		images.push_back( imread(path) );
		imshow("srcImg",images[i]);
		waitKey(100);
	}
	if(images.empty())
	{
		cout<<"images does not exist."<<endl;
	}
	
	//--step[3]: detect ORB features
	cout<<endl<<"step[3]: detecting ORB features ... "<<endl;
	vector<Mat> descriptors;
	vector<vector<Mat>> vvmfeatures;
	vvmfeatures.reserve(images.size());
	Ptr<Feature2D> detector =ORB::create();
	for ( Mat& image:images )
	{
		vector<KeyPoint> keypoints; 
		Mat descriptor;
		detector->detectAndCompute( image, Mat(), keypoints, descriptor );
		descriptors.push_back( descriptor );
		vvmfeatures.push_back(vector<Mat>());
		changeStructure(descriptor,vvmfeatures.back());
		
	}

	//--step[4]: compare with database 
	cout<<endl<<"step[4]: comparing images with database "<<endl;
	ORB_SLAM2::ORBDatabase db( vocab, false, 0);
	for ( int i=0; i<vvmfeatures.size(); i++ )
		db.add(vvmfeatures[i]);
	cout<<endl<<"database info: "<<db<<endl;
	DBoW2::QueryResults ret;
	for ( int i=0; i<vvmfeatures.size(); i++ )
	{
		db.query( vvmfeatures[i], ret, 4);	// max result=4
		cout<<endl<<"searching for image "<<i<<" returns "<<ret<<endl<<endl;
	}
	cout<<"done."<<endl;
	return 0;
}
  1. CMakeLists.txt
// 添加1 
add_executable(create_dbow_node node/create_dbow_node.cpp)
target_link_libraries(create_dbow_node
${PROJECT_NAME}
${catkin_LIBRARIES}
${OpenCV_LIBS}
${EIGEN3_LIBS}
${Pangolin_LIBRARIES}
${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so
${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
)
// 添加2 
add_executable( loadDBoW2_node node/loadDBoW2_node.cpp )
target_link_libraries( loadDBoW2_node
${PROJECT_NAME}
${catkin_LIBRARIES}
${OpenCV_LIBS}
${EIGEN3_LIBS}
${Pangolin_LIBRARIES}
${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so
${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so
)

参考blog

[1] 回环检测的DBoW词袋字典如何生成?
[2] ORBSLAM2学习(五):DBoW2源码分析(OrbDatabase部分)

  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值