ORB SLAM3 使用二进制文件 ORBvoc.bin 加载Vocabulary

使用 二进制文件 ORBvoc.bin 加载Vocabulary,将比ORBvoc.txt 速度快很多倍!

  实测1秒内完成加载:

一、下载ORBvoc.bin

百度网盘: ORBvoc.bin下载链接  提取码:dyyk

解压后,将ORBvoc.bin拷贝到Vocabulary文件夹下

二、修改代码

2.1  修改 Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h

①249 行在 “TextFile”类型 的下面 加入 loadFromBinaryFile() 函数 和   saveToBinaryFile() 函数的声明:

 /**
   * Loads the vocabulary from a binary file
   * @param filename
   */
  bool loadFromBinaryFile(const std::string &filename);

  /**
   * Saves the vocabulary into a binary file
   * @param filename
   */
  void saveToBinaryFile(const std::string &filename) const;  

如图: 

ORB SLAM3 使用二进制文件 ORBvoc.bin 加载Vocabulary_第1张图片 

② 加入上面两个函数的定义:

 我们就写在 1465行左右 的saveToTextFile()函数定义的后面 :

template
bool TemplatedVocabulary::loadFromBinaryFile(const std::string &filename) {
  fstream f;
  f.open(filename.c_str(), ios_base::in|ios::binary);
  unsigned int nb_nodes, size_node;
  f.read((char*)&nb_nodes, sizeof(nb_nodes));
  f.read((char*)&size_node, sizeof(size_node));
  f.read((char*)&m_k, sizeof(m_k));
  f.read((char*)&m_L, sizeof(m_L));
  f.read((char*)&m_scoring, sizeof(m_scoring));
  f.read((char*)&m_weighting, sizeof(m_weighting));
  createScoringObject();

  m_words.clear();
  m_words.reserve(pow((double)m_k, (double)m_L + 1));
  m_nodes.clear();
  m_nodes.resize(nb_nodes+1);
  m_nodes[0].id = 0;
  char buf[size_node]; int nid = 1;
  while (!f.eof()) {
	f.read(buf, size_node);
	m_nodes[nid].id = nid;
	// FIXME
	const int* ptr=(int*)buf;
	m_nodes[nid].parent = *ptr;
	//m_nodes[nid].parent = *(const int*)buf;
	m_nodes[m_nodes[nid].parent].children.push_back(nid);
	m_nodes[nid].descriptor = cv::Mat(1, F::L, CV_8U);
	memcpy(m_nodes[nid].descriptor.data, buf+4, F::L);
	m_nodes[nid].weight = *(float*)(buf+4+F::L);
	if (buf[8+F::L]) { // is leaf
	  int wid = m_words.size();
	  m_words.resize(wid+1);
	  m_nodes[nid].word_id = wid;
	  m_words[wid] = &m_nodes[nid];
	}
	else
	  m_nodes[nid].children.reserve(m_k);
	nid+=1;
  }
  f.close();
  return true;
}

// --------------------------------------------------------------------------

template
void TemplatedVocabulary::saveToBinaryFile(const std::string &filename) const {
  fstream f;
  f.open(filename.c_str(), ios_base::out|ios::binary);
  unsigned int nb_nodes = m_nodes.size();
  float _weight;
  unsigned int size_node = sizeof(m_nodes[0].parent) + F::L*sizeof(char) + sizeof(_weight) + sizeof(bool);
  f.write((char*)&nb_nodes, sizeof(nb_nodes));
  f.write((char*)&size_node, sizeof(size_node));
  f.write((char*)&m_k, sizeof(m_k));
  f.write((char*)&m_L, sizeof(m_L));
  f.write((char*)&m_scoring, sizeof(m_scoring));
  f.write((char*)&m_weighting, sizeof(m_weighting));
  for(size_t i=1; i

位置如图: 

ORB SLAM3 使用二进制文件 ORBvoc.bin 加载Vocabulary_第2张图片

 

2.2  修改 ORB_SLAM3/src/System.cc

修改加载词袋的类型为 :BinaryFile

mpVocabulary = new ORBVocabulary();
  //bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);   //txt加载
  bool bVocLoad = mpVocabulary->loadFromBinaryFile(strVocFile);   //bin加载

三、运行

3.1 重新编译ORB-SLAM3

./build.sh

3.2 运行

运行时,需要把原来加载词袋命令  ./Vocabulary/ORBvoc.txt  改成  ./Vocabulary/ORBvoc.bin

如运行 EuRoc 单目时:

./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.bin ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Monocular/EuRoC_TimeStamps/MH01.txt 

你可能感兴趣的:(ORB-SLAM3,SLAM,计算机视觉,ubuntu,c++)