Skip to content

Commit

Permalink
Make it possible to save/load binary vocabularies.
Browse files Browse the repository at this point in the history
  • Loading branch information
sgolodetz committed Aug 1, 2021
1 parent 448a400 commit 6b06402
Show file tree
Hide file tree
Showing 2 changed files with 108 additions and 5 deletions.
95 changes: 94 additions & 1 deletion Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
Original file line number Diff line number Diff line change
Expand Up @@ -244,7 +244,19 @@ class TemplatedVocabulary
* Saves the vocabulary into a text file
* @param filename
*/
void saveToTextFile(const std::string &filename) const;
void saveToTextFile(const std::string &filename) const;

/**
* 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;

/**
* Saves the vocabulary into a file
Expand Down Expand Up @@ -1450,6 +1462,87 @@ void TemplatedVocabulary<TDescriptor,F>::saveToTextFile(const std::string &filen

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

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 = new char[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;
}
delete[] buf;
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 alignment....
}
f.close();
}

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

template<class TDescriptor, class F>
void TemplatedVocabulary<TDescriptor,F>::save(const std::string &filename) const
{
Expand Down
18 changes: 14 additions & 4 deletions src/System.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,12 @@
#include <pangolin/pangolin.h>
#include <iomanip>

bool has_suffix(const string &str, const string &suffix)
{
std::size_t index = str.find(suffix, str.size() - suffix.size());
return (index != string::npos);
}

namespace ORB_SLAM2
{

Expand Down Expand Up @@ -60,16 +66,20 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS

//Load ORB Vocabulary
cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl;

clock_t tStart = clock();
mpVocabulary = new ORBVocabulary();
bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
bool bVocLoad = false; // choose loading method based on file extension
if (has_suffix(strVocFile, ".txt"))
bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
else
bVocLoad = mpVocabulary->loadFromBinaryFile(strVocFile);
if(!bVocLoad)
{
cerr << "Wrong path to vocabulary. " << endl;
cerr << "Falied to open at: " << strVocFile << endl;
cerr << "Failed to open at: " << strVocFile << endl;
exit(-1);
}
cout << "Vocabulary loaded!" << endl << endl;
printf("Vocabulary loaded in %.2fs\n", (double)(clock() - tStart)/CLOCKS_PER_SEC);

//Create KeyFrame Database
mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);
Expand Down

0 comments on commit 6b06402

Please sign in to comment.