Use the binary file ORBvoc.bin to load Vocabulary, which will be many times faster than ORBvoc.txt!
Actual measurement: Loading completed within 1 second:
1. Download ORBvoc.bin
Baidu Netdisk: ORBvoc.bin download link Extraction code: dyyk
After unzipping, copy ORBvoc.bin to the Vocabulary folder
2. Modify the code
2.1 Modify Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
①In line 249, add the declarations of the loadFromBinaryFile() function and saveToBinaryFile() function under the "TextFile" type:
/**
* 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;
As shown in the picture:
② Add the definitions of the above two functions:
We write it just after the saveToTextFile() function definition on line 1465 or so:
template<class TDescriptor, class F>
bool TemplatedVocabulary<TDescriptor,F>::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<class TDescriptor, class F>
void TemplatedVocabulary<TDescriptor,F>::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<nb_nodes;i++) {
const Node& node = m_nodes[i];
f.write((char*)&node.parent, sizeof(node.parent));
f.write((char*)node.descriptor.data, F::L);
_weight = node.weight; f.write((char*)&_weight, sizeof(_weight));
bool is_leaf = node.isLeaf(); f.write((char*)&is_leaf, sizeof(is_leaf)); // i put this one at the end for alignement....
}
f.close();
}
// --------------------------------------------------------------------------
The location is as shown in the picture:
2.2 Modify ORB_SLAM3/src/System.cc
Modify the type of loaded word bag to: BinaryFile
mpVocabulary = new ORBVocabulary();
//bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile); //txt加载
bool bVocLoad = mpVocabulary->loadFromBinaryFile(strVocFile); //bin加载
3. Operation
3.1 Recompile ORB-SLAM3
./build.sh
3.2 Operation
When running, you need to change the original bag-of-words command ./Vocabulary/ORBvoc.txt to ./Vocabulary/ORBvoc.bin
For example, when running EuRoc monocular:
./Examples/Monocular/mono_euroc ./Vocabulary/ORBvoc.bin ./Examples/Monocular/EuRoC.yaml "$pathDatasetEuroc"/MH01 ./Examples/Monocular/EuRoC_TimeStamps/MH01.txt