Skip to content

Commit

Permalink
add binary and text read of vocabularies as done in raulmur/ORB_SLAM2#21
Browse files Browse the repository at this point in the history
  • Loading branch information
tshellum committed Apr 7, 2021
1 parent 3924753 commit 7bfc167
Show file tree
Hide file tree
Showing 4 changed files with 273 additions and 0 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
/build
/tools/bin_vocabulary
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -63,3 +63,8 @@ install(FILES "${PROJECT_BINARY_DIR}/DBoW2Config.cmake"
DESTINATION ${CMAKE_INSTALL_PREFIX}/lib/cmake/DBoW2/)
install(DIRECTORY ${DEPENDENCY_INSTALL_DIR}/ DESTINATION ${CMAKE_INSTALL_PREFIX} OPTIONAL)

# Build tools
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/tools)
add_executable(bin_vocabulary
tools/bin_vocabulary.cc)
target_link_libraries(bin_vocabulary ${PROJECT_NAME})
214 changes: 214 additions & 0 deletions include/DBoW2/TemplatedVocabulary.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#include "BowVector.h"
#include "ScoringObject.h"

using namespace std;

namespace DBoW2 {

/// @param TDescriptor class of descriptor
Expand Down Expand Up @@ -234,6 +236,30 @@ class TemplatedVocabulary
*/
void load(const std::string &filename);

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

/**
* Saves the vocabulary into a text file
* @param filename
*/
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 to a file storage structure
* @param fn node in file storage
Expand Down Expand Up @@ -1505,6 +1531,194 @@ void TemplatedVocabulary<TDescriptor,F>::load(const cv::FileStorage &fs,

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

template<class TDescriptor, class F>
bool TemplatedVocabulary<TDescriptor,F>::loadFromTextFile(const std::string &filename)
{
ifstream f;
f.open(filename.c_str());

if(f.eof())
return false;

m_words.clear();
m_nodes.clear();

string s;
getline(f,s);
stringstream ss;
ss << s;
ss >> m_k;
ss >> m_L;
int n1, n2;
ss >> n1;
ss >> n2;

if(m_k<0 || m_k>20 || m_L<1 || m_L>10 || n1<0 || n1>5 || n2<0 || n2>3)
{
std::cerr << "Vocabulary loading failure: This is not a correct text file!" << endl;
return false;
}

m_scoring = (ScoringType)n1;
m_weighting = (WeightingType)n2;
createScoringObject();

// nodes
int expected_nodes =
(int)((pow((double)m_k, (double)m_L + 1) - 1)/(m_k - 1));
m_nodes.reserve(expected_nodes);

m_words.reserve(pow((double)m_k, (double)m_L + 1));

m_nodes.resize(1);
m_nodes[0].id = 0;
while(!f.eof())
{
string snode;
getline(f,snode);
stringstream ssnode;
ssnode << snode;

int nid = m_nodes.size();
m_nodes.resize(m_nodes.size()+1);
m_nodes[nid].id = nid;

int pid ;
ssnode >> pid;
m_nodes[nid].parent = pid;
m_nodes[pid].children.push_back(nid);

int nIsLeaf;
ssnode >> nIsLeaf;

stringstream ssd;
for(int iD=0;iD<F::L;iD++)
{
string sElement;
ssnode >> sElement;
ssd << sElement << " ";
}
F::fromString(m_nodes[nid].descriptor, ssd.str());

ssnode >> m_nodes[nid].weight;

if(nIsLeaf>0)
{
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);
}
}

return true;

}

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

template<class TDescriptor, class F>
void TemplatedVocabulary<TDescriptor,F>::saveToTextFile(const std::string &filename) const
{
fstream f;
f.open(filename.c_str(),ios_base::out);
f << m_k << " " << m_L << " " << " " << m_scoring << " " << m_weighting << endl;

for(size_t i=1; i<m_nodes.size();i++)
{
const Node& node = m_nodes[i];

f << node.parent << " ";
if(node.isLeaf())
f << 1 << " ";
else
f << 0 << " ";

f << F::toString(node.descriptor) << " " << (double)node.weight << endl;
}

f.close();
}

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

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();
}

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

/**
* Writes printable information of the vocabulary
* @param os stream to write to
Expand Down
52 changes: 52 additions & 0 deletions tools/bin_vocabulary.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
#include <time.h>

#include "../include/DBoW2/DBoW2.h"
using namespace std;

bool load_as_text(OrbVocabulary* voc, const std::string infile) {
clock_t tStart = clock();
bool res = voc->loadFromTextFile(infile);
printf("Loading fom text: %.2fs\n", (double)(clock() - tStart)/CLOCKS_PER_SEC);
return res;
}

void load_as_xml(OrbVocabulary* voc, const std::string infile) {
clock_t tStart = clock();
voc->load(infile);
printf("Loading fom xml: %.2fs\n", (double)(clock() - tStart)/CLOCKS_PER_SEC);
}

void load_as_binary(OrbVocabulary* voc, const std::string infile) {
clock_t tStart = clock();
voc->loadFromBinaryFile(infile);
printf("Loading fom binary: %.2fs\n", (double)(clock() - tStart)/CLOCKS_PER_SEC);
}

void save_as_xml(OrbVocabulary* voc, const std::string outfile) {
clock_t tStart = clock();
voc->save(outfile);
printf("Saving as xml: %.2fs\n", (double)(clock() - tStart)/CLOCKS_PER_SEC);
}

void save_as_text(OrbVocabulary* voc, const std::string outfile) {
clock_t tStart = clock();
voc->saveToTextFile(outfile);
printf("Saving as text: %.2fs\n", (double)(clock() - tStart)/CLOCKS_PER_SEC);
}

void save_as_binary(OrbVocabulary* voc, const std::string outfile) {
clock_t tStart = clock();
voc->saveToBinaryFile(outfile);
printf("Saving as binary: %.2fs\n", (double)(clock() - tStart)/CLOCKS_PER_SEC);
}


int main(int argc, char **argv) {
cout << "BoW load/save benchmark" << endl;
OrbVocabulary* voc = new OrbVocabulary();

load_as_text(voc, "ORBvoc.txt");
save_as_binary(voc, "ORBvoc.bin");

return 0;
}

0 comments on commit 7bfc167

Please sign in to comment.