raw
This commit is contained in:
130
Thirdparty/DBoW2/DBoW2/BowVector.cpp
vendored
Normal file
130
Thirdparty/DBoW2/DBoW2/BowVector.cpp
vendored
Normal file
@@ -0,0 +1,130 @@
|
||||
/**
|
||||
* File: BowVector.cpp
|
||||
* Date: March 2011
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: bag of words vector
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <vector>
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
|
||||
#include "BowVector.h"
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
BowVector::BowVector(void)
|
||||
{
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
BowVector::~BowVector(void)
|
||||
{
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void BowVector::addWeight(WordId id, WordValue v)
|
||||
{
|
||||
BowVector::iterator vit = this->lower_bound(id);
|
||||
|
||||
if(vit != this->end() && !(this->key_comp()(id, vit->first)))
|
||||
{
|
||||
vit->second += v;
|
||||
}
|
||||
else
|
||||
{
|
||||
this->insert(vit, BowVector::value_type(id, v));
|
||||
}
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void BowVector::addIfNotExist(WordId id, WordValue v)
|
||||
{
|
||||
BowVector::iterator vit = this->lower_bound(id);
|
||||
|
||||
if(vit == this->end() || (this->key_comp()(id, vit->first)))
|
||||
{
|
||||
this->insert(vit, BowVector::value_type(id, v));
|
||||
}
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void BowVector::normalize(LNorm norm_type)
|
||||
{
|
||||
double norm = 0.0;
|
||||
BowVector::iterator it;
|
||||
|
||||
if(norm_type == DBoW2::L1)
|
||||
{
|
||||
for(it = begin(); it != end(); ++it)
|
||||
norm += fabs(it->second);
|
||||
}
|
||||
else
|
||||
{
|
||||
for(it = begin(); it != end(); ++it)
|
||||
norm += it->second * it->second;
|
||||
norm = sqrt(norm);
|
||||
}
|
||||
|
||||
if(norm > 0.0)
|
||||
{
|
||||
for(it = begin(); it != end(); ++it)
|
||||
it->second /= norm;
|
||||
}
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
std::ostream& operator<< (std::ostream &out, const BowVector &v)
|
||||
{
|
||||
BowVector::const_iterator vit;
|
||||
std::vector<unsigned int>::const_iterator iit;
|
||||
unsigned int i = 0;
|
||||
const unsigned int N = v.size();
|
||||
for(vit = v.begin(); vit != v.end(); ++vit, ++i)
|
||||
{
|
||||
out << "<" << vit->first << ", " << vit->second << ">";
|
||||
|
||||
if(i < N-1) out << ", ";
|
||||
}
|
||||
return out;
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void BowVector::saveM(const std::string &filename, size_t W) const
|
||||
{
|
||||
std::fstream f(filename.c_str(), std::ios::out);
|
||||
|
||||
WordId last = 0;
|
||||
BowVector::const_iterator bit;
|
||||
for(bit = this->begin(); bit != this->end(); ++bit)
|
||||
{
|
||||
for(; last < bit->first; ++last)
|
||||
{
|
||||
f << "0 ";
|
||||
}
|
||||
f << bit->second << " ";
|
||||
|
||||
last = bit->first + 1;
|
||||
}
|
||||
for(; last < (WordId)W; ++last)
|
||||
f << "0 ";
|
||||
|
||||
f.close();
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
} // namespace DBoW2
|
||||
|
||||
119
Thirdparty/DBoW2/DBoW2/BowVector.h
vendored
Normal file
119
Thirdparty/DBoW2/DBoW2/BowVector.h
vendored
Normal file
@@ -0,0 +1,119 @@
|
||||
/**
|
||||
* File: BowVector.h
|
||||
* Date: March 2011
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: bag of words vector
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __D_T_BOW_VECTOR__
|
||||
#define __D_T_BOW_VECTOR__
|
||||
|
||||
#include <iostream>
|
||||
#include <map>
|
||||
#include <vector>
|
||||
|
||||
#include <boost/serialization/serialization.hpp>
|
||||
#include <boost/serialization/map.hpp>
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
/// Id of words
|
||||
typedef unsigned int WordId;
|
||||
|
||||
/// Value of a word
|
||||
typedef double WordValue;
|
||||
|
||||
/// Id of nodes in the vocabulary treee
|
||||
typedef unsigned int NodeId;
|
||||
|
||||
/// L-norms for normalization
|
||||
enum LNorm
|
||||
{
|
||||
L1,
|
||||
L2
|
||||
};
|
||||
|
||||
/// Weighting type
|
||||
enum WeightingType
|
||||
{
|
||||
TF_IDF,
|
||||
TF,
|
||||
IDF,
|
||||
BINARY
|
||||
};
|
||||
|
||||
/// Scoring type
|
||||
enum ScoringType
|
||||
{
|
||||
L1_NORM,
|
||||
L2_NORM,
|
||||
CHI_SQUARE,
|
||||
KL,
|
||||
BHATTACHARYYA,
|
||||
DOT_PRODUCT,
|
||||
};
|
||||
|
||||
/// Vector of words to represent images
|
||||
class BowVector:
|
||||
public std::map<WordId, WordValue>
|
||||
{
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive& ar, const int version)
|
||||
{
|
||||
ar & boost::serialization::base_object<std::map<WordId, WordValue> >(*this);
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
BowVector(void);
|
||||
|
||||
/**
|
||||
* Destructor
|
||||
*/
|
||||
~BowVector(void);
|
||||
|
||||
/**
|
||||
* Adds a value to a word value existing in the vector, or creates a new
|
||||
* word with the given value
|
||||
* @param id word id to look for
|
||||
* @param v value to create the word with, or to add to existing word
|
||||
*/
|
||||
void addWeight(WordId id, WordValue v);
|
||||
|
||||
/**
|
||||
* Adds a word with a value to the vector only if this does not exist yet
|
||||
* @param id word id to look for
|
||||
* @param v value to give to the word if this does not exist
|
||||
*/
|
||||
void addIfNotExist(WordId id, WordValue v);
|
||||
|
||||
/**
|
||||
* L1-Normalizes the values in the vector
|
||||
* @param norm_type norm used
|
||||
*/
|
||||
void normalize(LNorm norm_type);
|
||||
|
||||
/**
|
||||
* Prints the content of the bow vector
|
||||
* @param out stream
|
||||
* @param v
|
||||
*/
|
||||
friend std::ostream& operator<<(std::ostream &out, const BowVector &v);
|
||||
|
||||
/**
|
||||
* Saves the bow vector as a vector in a matlab file
|
||||
* @param filename
|
||||
* @param W number of words in the vocabulary
|
||||
*/
|
||||
void saveM(const std::string &filename, size_t W) const;
|
||||
};
|
||||
|
||||
} // namespace DBoW2
|
||||
|
||||
#endif
|
||||
71
Thirdparty/DBoW2/DBoW2/FClass.h
vendored
Normal file
71
Thirdparty/DBoW2/DBoW2/FClass.h
vendored
Normal file
@@ -0,0 +1,71 @@
|
||||
/**
|
||||
* File: FClass.h
|
||||
* Date: November 2011
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: generic FClass to instantiate templated classes
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __D_T_FCLASS__
|
||||
#define __D_T_FCLASS__
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
/// Generic class to encapsulate functions to manage descriptors.
|
||||
/**
|
||||
* This class must be inherited. Derived classes can be used as the
|
||||
* parameter F when creating Templated structures
|
||||
* (TemplatedVocabulary, TemplatedDatabase, ...)
|
||||
*/
|
||||
class FClass
|
||||
{
|
||||
class TDescriptor;
|
||||
typedef const TDescriptor *pDescriptor;
|
||||
|
||||
/**
|
||||
* Calculates the mean value of a set of descriptors
|
||||
* @param descriptors
|
||||
* @param mean mean descriptor
|
||||
*/
|
||||
virtual void meanValue(const std::vector<pDescriptor> &descriptors,
|
||||
TDescriptor &mean) = 0;
|
||||
|
||||
/**
|
||||
* Calculates the distance between two descriptors
|
||||
* @param a
|
||||
* @param b
|
||||
* @return distance
|
||||
*/
|
||||
static double distance(const TDescriptor &a, const TDescriptor &b);
|
||||
|
||||
/**
|
||||
* Returns a string version of the descriptor
|
||||
* @param a descriptor
|
||||
* @return string version
|
||||
*/
|
||||
static std::string toString(const TDescriptor &a);
|
||||
|
||||
/**
|
||||
* Returns a descriptor from a string
|
||||
* @param a descriptor
|
||||
* @param s string version
|
||||
*/
|
||||
static void fromString(TDescriptor &a, const std::string &s);
|
||||
|
||||
/**
|
||||
* Returns a mat with the descriptors in float format
|
||||
* @param descriptors
|
||||
* @param mat (out) NxL 32F matrix
|
||||
*/
|
||||
static void toMat32F(const std::vector<TDescriptor> &descriptors,
|
||||
cv::Mat &mat);
|
||||
};
|
||||
|
||||
} // namespace DBoW2
|
||||
|
||||
#endif
|
||||
193
Thirdparty/DBoW2/DBoW2/FORB.cpp
vendored
Normal file
193
Thirdparty/DBoW2/DBoW2/FORB.cpp
vendored
Normal file
@@ -0,0 +1,193 @@
|
||||
/**
|
||||
* File: FORB.cpp
|
||||
* Date: June 2012
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: functions for ORB descriptors
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
* Distance function has been modified
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
#include <vector>
|
||||
#include <string>
|
||||
#include <sstream>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "FORB.h"
|
||||
|
||||
using namespace std;
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
const int FORB::L=32;
|
||||
|
||||
void FORB::meanValue(const std::vector<FORB::pDescriptor> &descriptors,
|
||||
FORB::TDescriptor &mean)
|
||||
{
|
||||
if(descriptors.empty())
|
||||
{
|
||||
mean.release();
|
||||
return;
|
||||
}
|
||||
else if(descriptors.size() == 1)
|
||||
{
|
||||
mean = descriptors[0]->clone();
|
||||
}
|
||||
else
|
||||
{
|
||||
vector<int> sum(FORB::L * 8, 0);
|
||||
|
||||
for(size_t i = 0; i < descriptors.size(); ++i)
|
||||
{
|
||||
const cv::Mat &d = *descriptors[i];
|
||||
const unsigned char *p = d.ptr<unsigned char>();
|
||||
|
||||
for(int j = 0; j < d.cols; ++j, ++p)
|
||||
{
|
||||
if(*p & (1 << 7)) ++sum[ j*8 ];
|
||||
if(*p & (1 << 6)) ++sum[ j*8 + 1 ];
|
||||
if(*p & (1 << 5)) ++sum[ j*8 + 2 ];
|
||||
if(*p & (1 << 4)) ++sum[ j*8 + 3 ];
|
||||
if(*p & (1 << 3)) ++sum[ j*8 + 4 ];
|
||||
if(*p & (1 << 2)) ++sum[ j*8 + 5 ];
|
||||
if(*p & (1 << 1)) ++sum[ j*8 + 6 ];
|
||||
if(*p & (1)) ++sum[ j*8 + 7 ];
|
||||
}
|
||||
}
|
||||
|
||||
mean = cv::Mat::zeros(1, FORB::L, CV_8U);
|
||||
unsigned char *p = mean.ptr<unsigned char>();
|
||||
|
||||
const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2;
|
||||
for(size_t i = 0; i < sum.size(); ++i)
|
||||
{
|
||||
if(sum[i] >= N2)
|
||||
{
|
||||
// set bit
|
||||
*p |= 1 << (7 - (i % 8));
|
||||
}
|
||||
|
||||
if(i % 8 == 7) ++p;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
int FORB::distance(const FORB::TDescriptor &a,
|
||||
const FORB::TDescriptor &b)
|
||||
{
|
||||
// Bit set count operation from
|
||||
// http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel
|
||||
|
||||
const int *pa = a.ptr<int32_t>();
|
||||
const int *pb = b.ptr<int32_t>();
|
||||
|
||||
int dist=0;
|
||||
|
||||
for(int i=0; i<8; i++, pa++, pb++)
|
||||
{
|
||||
unsigned int v = *pa ^ *pb;
|
||||
v = v - ((v >> 1) & 0x55555555);
|
||||
v = (v & 0x33333333) + ((v >> 2) & 0x33333333);
|
||||
dist += (((v + (v >> 4)) & 0xF0F0F0F) * 0x1010101) >> 24;
|
||||
}
|
||||
|
||||
return dist;
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
std::string FORB::toString(const FORB::TDescriptor &a)
|
||||
{
|
||||
stringstream ss;
|
||||
const unsigned char *p = a.ptr<unsigned char>();
|
||||
|
||||
for(int i = 0; i < a.cols; ++i, ++p)
|
||||
{
|
||||
ss << (int)*p << " ";
|
||||
}
|
||||
|
||||
return ss.str();
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void FORB::fromString(FORB::TDescriptor &a, const std::string &s)
|
||||
{
|
||||
a.create(1, FORB::L, CV_8U);
|
||||
unsigned char *p = a.ptr<unsigned char>();
|
||||
|
||||
stringstream ss(s);
|
||||
for(int i = 0; i < FORB::L; ++i, ++p)
|
||||
{
|
||||
int n;
|
||||
ss >> n;
|
||||
|
||||
if(!ss.fail())
|
||||
*p = (unsigned char)n;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void FORB::toMat32F(const std::vector<TDescriptor> &descriptors,
|
||||
cv::Mat &mat)
|
||||
{
|
||||
if(descriptors.empty())
|
||||
{
|
||||
mat.release();
|
||||
return;
|
||||
}
|
||||
|
||||
const size_t N = descriptors.size();
|
||||
|
||||
mat.create(N, FORB::L*8, CV_32F);
|
||||
float *p = mat.ptr<float>();
|
||||
|
||||
for(size_t i = 0; i < N; ++i)
|
||||
{
|
||||
const int C = descriptors[i].cols;
|
||||
const unsigned char *desc = descriptors[i].ptr<unsigned char>();
|
||||
|
||||
for(int j = 0; j < C; ++j, p += 8)
|
||||
{
|
||||
p[0] = (desc[j] & (1 << 7) ? 1 : 0);
|
||||
p[1] = (desc[j] & (1 << 6) ? 1 : 0);
|
||||
p[2] = (desc[j] & (1 << 5) ? 1 : 0);
|
||||
p[3] = (desc[j] & (1 << 4) ? 1 : 0);
|
||||
p[4] = (desc[j] & (1 << 3) ? 1 : 0);
|
||||
p[5] = (desc[j] & (1 << 2) ? 1 : 0);
|
||||
p[6] = (desc[j] & (1 << 1) ? 1 : 0);
|
||||
p[7] = desc[j] & (1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
void FORB::toMat8U(const std::vector<TDescriptor> &descriptors,
|
||||
cv::Mat &mat)
|
||||
{
|
||||
mat.create(descriptors.size(), 32, CV_8U);
|
||||
|
||||
unsigned char *p = mat.ptr<unsigned char>();
|
||||
|
||||
for(size_t i = 0; i < descriptors.size(); ++i, p += 32)
|
||||
{
|
||||
const unsigned char *d = descriptors[i].ptr<unsigned char>();
|
||||
std::copy(d, d+32, p);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// --------------------------------------------------------------------------
|
||||
|
||||
} // namespace DBoW2
|
||||
|
||||
|
||||
79
Thirdparty/DBoW2/DBoW2/FORB.h
vendored
Normal file
79
Thirdparty/DBoW2/DBoW2/FORB.h
vendored
Normal file
@@ -0,0 +1,79 @@
|
||||
/**
|
||||
* File: FORB.h
|
||||
* Date: June 2012
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: functions for ORB descriptors
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __D_T_F_ORB__
|
||||
#define __D_T_F_ORB__
|
||||
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <vector>
|
||||
#include <string>
|
||||
|
||||
#include "FClass.h"
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
/// Functions to manipulate ORB descriptors
|
||||
class FORB: protected FClass
|
||||
{
|
||||
public:
|
||||
|
||||
/// Descriptor type
|
||||
typedef cv::Mat TDescriptor; // CV_8U
|
||||
/// Pointer to a single descriptor
|
||||
typedef const TDescriptor *pDescriptor;
|
||||
/// Descriptor length (in bytes)
|
||||
static const int L;
|
||||
|
||||
/**
|
||||
* Calculates the mean value of a set of descriptors
|
||||
* @param descriptors
|
||||
* @param mean mean descriptor
|
||||
*/
|
||||
static void meanValue(const std::vector<pDescriptor> &descriptors,
|
||||
TDescriptor &mean);
|
||||
|
||||
/**
|
||||
* Calculates the distance between two descriptors
|
||||
* @param a
|
||||
* @param b
|
||||
* @return distance
|
||||
*/
|
||||
static int distance(const TDescriptor &a, const TDescriptor &b);
|
||||
|
||||
/**
|
||||
* Returns a string version of the descriptor
|
||||
* @param a descriptor
|
||||
* @return string version
|
||||
*/
|
||||
static std::string toString(const TDescriptor &a);
|
||||
|
||||
/**
|
||||
* Returns a descriptor from a string
|
||||
* @param a descriptor
|
||||
* @param s string version
|
||||
*/
|
||||
static void fromString(TDescriptor &a, const std::string &s);
|
||||
|
||||
/**
|
||||
* Returns a mat with the descriptors in float format
|
||||
* @param descriptors
|
||||
* @param mat (out) NxL 32F matrix
|
||||
*/
|
||||
static void toMat32F(const std::vector<TDescriptor> &descriptors,
|
||||
cv::Mat &mat);
|
||||
|
||||
static void toMat8U(const std::vector<TDescriptor> &descriptors,
|
||||
cv::Mat &mat);
|
||||
|
||||
};
|
||||
|
||||
} // namespace DBoW2
|
||||
|
||||
#endif
|
||||
|
||||
85
Thirdparty/DBoW2/DBoW2/FeatureVector.cpp
vendored
Normal file
85
Thirdparty/DBoW2/DBoW2/FeatureVector.cpp
vendored
Normal file
@@ -0,0 +1,85 @@
|
||||
/**
|
||||
* File: FeatureVector.cpp
|
||||
* Date: November 2011
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: feature vector
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#include "FeatureVector.h"
|
||||
#include <map>
|
||||
#include <vector>
|
||||
#include <iostream>
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
FeatureVector::FeatureVector(void)
|
||||
{
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
FeatureVector::~FeatureVector(void)
|
||||
{
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
void FeatureVector::addFeature(NodeId id, unsigned int i_feature)
|
||||
{
|
||||
FeatureVector::iterator vit = this->lower_bound(id);
|
||||
|
||||
if(vit != this->end() && vit->first == id)
|
||||
{
|
||||
vit->second.push_back(i_feature);
|
||||
}
|
||||
else
|
||||
{
|
||||
vit = this->insert(vit, FeatureVector::value_type(id,
|
||||
std::vector<unsigned int>() ));
|
||||
vit->second.push_back(i_feature);
|
||||
}
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
std::ostream& operator<<(std::ostream &out,
|
||||
const FeatureVector &v)
|
||||
{
|
||||
if(!v.empty())
|
||||
{
|
||||
FeatureVector::const_iterator vit = v.begin();
|
||||
|
||||
const std::vector<unsigned int>* f = &vit->second;
|
||||
|
||||
out << "<" << vit->first << ": [";
|
||||
if(!f->empty()) out << (*f)[0];
|
||||
for(unsigned int i = 1; i < f->size(); ++i)
|
||||
{
|
||||
out << ", " << (*f)[i];
|
||||
}
|
||||
out << "]>";
|
||||
|
||||
for(++vit; vit != v.end(); ++vit)
|
||||
{
|
||||
f = &vit->second;
|
||||
|
||||
out << ", <" << vit->first << ": [";
|
||||
if(!f->empty()) out << (*f)[0];
|
||||
for(unsigned int i = 1; i < f->size(); ++i)
|
||||
{
|
||||
out << ", " << (*f)[i];
|
||||
}
|
||||
out << "]>";
|
||||
}
|
||||
}
|
||||
|
||||
return out;
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
} // namespace DBoW2
|
||||
66
Thirdparty/DBoW2/DBoW2/FeatureVector.h
vendored
Normal file
66
Thirdparty/DBoW2/DBoW2/FeatureVector.h
vendored
Normal file
@@ -0,0 +1,66 @@
|
||||
/**
|
||||
* File: FeatureVector.h
|
||||
* Date: November 2011
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: feature vector
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __D_T_FEATURE_VECTOR__
|
||||
#define __D_T_FEATURE_VECTOR__
|
||||
|
||||
#include "BowVector.h"
|
||||
#include <map>
|
||||
#include <vector>
|
||||
#include <iostream>
|
||||
|
||||
#include <boost/serialization/serialization.hpp>
|
||||
#include <boost/serialization/map.hpp>
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
/// Vector of nodes with indexes of local features
|
||||
class FeatureVector:
|
||||
public std::map<NodeId, std::vector<unsigned int> >
|
||||
{
|
||||
friend class boost::serialization::access;
|
||||
template<class Archive>
|
||||
void serialize(Archive& ar, const int version)
|
||||
{
|
||||
ar & boost::serialization::base_object<std::map<NodeId, std::vector<unsigned int> > >(*this);
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
FeatureVector(void);
|
||||
|
||||
/**
|
||||
* Destructor
|
||||
*/
|
||||
~FeatureVector(void);
|
||||
|
||||
/**
|
||||
* Adds a feature to an existing node, or adds a new node with an initial
|
||||
* feature
|
||||
* @param id node id to add or to modify
|
||||
* @param i_feature index of feature to add to the given node
|
||||
*/
|
||||
void addFeature(NodeId id, unsigned int i_feature);
|
||||
|
||||
/**
|
||||
* Sends a string versions of the feature vector through the stream
|
||||
* @param out stream
|
||||
* @param v feature vector
|
||||
*/
|
||||
friend std::ostream& operator<<(std::ostream &out, const FeatureVector &v);
|
||||
|
||||
};
|
||||
|
||||
} // namespace DBoW2
|
||||
|
||||
#endif
|
||||
|
||||
315
Thirdparty/DBoW2/DBoW2/ScoringObject.cpp
vendored
Normal file
315
Thirdparty/DBoW2/DBoW2/ScoringObject.cpp
vendored
Normal file
@@ -0,0 +1,315 @@
|
||||
/**
|
||||
* File: ScoringObject.cpp
|
||||
* Date: November 2011
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: functions to compute bow scores
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#include <cfloat>
|
||||
#include "TemplatedVocabulary.h"
|
||||
#include "BowVector.h"
|
||||
|
||||
using namespace DBoW2;
|
||||
|
||||
// If you change the type of WordValue, make sure you change also the
|
||||
// epsilon value (this is needed by the KL method)
|
||||
const double GeneralScoring::LOG_EPS = log(DBL_EPSILON); // FLT_EPSILON
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
double L1Scoring::score(const BowVector &v1, const BowVector &v2) const
|
||||
{
|
||||
BowVector::const_iterator v1_it, v2_it;
|
||||
const BowVector::const_iterator v1_end = v1.end();
|
||||
const BowVector::const_iterator v2_end = v2.end();
|
||||
|
||||
v1_it = v1.begin();
|
||||
v2_it = v2.begin();
|
||||
|
||||
double score = 0;
|
||||
|
||||
while(v1_it != v1_end && v2_it != v2_end)
|
||||
{
|
||||
const WordValue& vi = v1_it->second;
|
||||
const WordValue& wi = v2_it->second;
|
||||
|
||||
if(v1_it->first == v2_it->first)
|
||||
{
|
||||
score += fabs(vi - wi) - fabs(vi) - fabs(wi);
|
||||
|
||||
// move v1 and v2 forward
|
||||
++v1_it;
|
||||
++v2_it;
|
||||
}
|
||||
else if(v1_it->first < v2_it->first)
|
||||
{
|
||||
// move v1 forward
|
||||
v1_it = v1.lower_bound(v2_it->first);
|
||||
// v1_it = (first element >= v2_it.id)
|
||||
}
|
||||
else
|
||||
{
|
||||
// move v2 forward
|
||||
v2_it = v2.lower_bound(v1_it->first);
|
||||
// v2_it = (first element >= v1_it.id)
|
||||
}
|
||||
}
|
||||
|
||||
// ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|)
|
||||
// for all i | v_i != 0 and w_i != 0
|
||||
// (Nister, 2006)
|
||||
// scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1}
|
||||
score = -score/2.0;
|
||||
|
||||
return score; // [0..1]
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
double L2Scoring::score(const BowVector &v1, const BowVector &v2) const
|
||||
{
|
||||
BowVector::const_iterator v1_it, v2_it;
|
||||
const BowVector::const_iterator v1_end = v1.end();
|
||||
const BowVector::const_iterator v2_end = v2.end();
|
||||
|
||||
v1_it = v1.begin();
|
||||
v2_it = v2.begin();
|
||||
|
||||
double score = 0;
|
||||
|
||||
while(v1_it != v1_end && v2_it != v2_end)
|
||||
{
|
||||
const WordValue& vi = v1_it->second;
|
||||
const WordValue& wi = v2_it->second;
|
||||
|
||||
if(v1_it->first == v2_it->first)
|
||||
{
|
||||
score += vi * wi;
|
||||
|
||||
// move v1 and v2 forward
|
||||
++v1_it;
|
||||
++v2_it;
|
||||
}
|
||||
else if(v1_it->first < v2_it->first)
|
||||
{
|
||||
// move v1 forward
|
||||
v1_it = v1.lower_bound(v2_it->first);
|
||||
// v1_it = (first element >= v2_it.id)
|
||||
}
|
||||
else
|
||||
{
|
||||
// move v2 forward
|
||||
v2_it = v2.lower_bound(v1_it->first);
|
||||
// v2_it = (first element >= v1_it.id)
|
||||
}
|
||||
}
|
||||
|
||||
// ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) )
|
||||
// for all i | v_i != 0 and w_i != 0 )
|
||||
// (Nister, 2006)
|
||||
if(score >= 1) // rounding errors
|
||||
score = 1.0;
|
||||
else
|
||||
score = 1.0 - sqrt(1.0 - score); // [0..1]
|
||||
|
||||
return score;
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
double ChiSquareScoring::score(const BowVector &v1, const BowVector &v2)
|
||||
const
|
||||
{
|
||||
BowVector::const_iterator v1_it, v2_it;
|
||||
const BowVector::const_iterator v1_end = v1.end();
|
||||
const BowVector::const_iterator v2_end = v2.end();
|
||||
|
||||
v1_it = v1.begin();
|
||||
v2_it = v2.begin();
|
||||
|
||||
double score = 0;
|
||||
|
||||
// all the items are taken into account
|
||||
|
||||
while(v1_it != v1_end && v2_it != v2_end)
|
||||
{
|
||||
const WordValue& vi = v1_it->second;
|
||||
const WordValue& wi = v2_it->second;
|
||||
|
||||
if(v1_it->first == v2_it->first)
|
||||
{
|
||||
// (v-w)^2/(v+w) - v - w = -4 vw/(v+w)
|
||||
// we move the -4 out
|
||||
if(vi + wi != 0.0) score += vi * wi / (vi + wi);
|
||||
|
||||
// move v1 and v2 forward
|
||||
++v1_it;
|
||||
++v2_it;
|
||||
}
|
||||
else if(v1_it->first < v2_it->first)
|
||||
{
|
||||
// move v1 forward
|
||||
v1_it = v1.lower_bound(v2_it->first);
|
||||
}
|
||||
else
|
||||
{
|
||||
// move v2 forward
|
||||
v2_it = v2.lower_bound(v1_it->first);
|
||||
}
|
||||
}
|
||||
|
||||
// this takes the -4 into account
|
||||
score = 2. * score; // [0..1]
|
||||
|
||||
return score;
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
double KLScoring::score(const BowVector &v1, const BowVector &v2) const
|
||||
{
|
||||
BowVector::const_iterator v1_it, v2_it;
|
||||
const BowVector::const_iterator v1_end = v1.end();
|
||||
const BowVector::const_iterator v2_end = v2.end();
|
||||
|
||||
v1_it = v1.begin();
|
||||
v2_it = v2.begin();
|
||||
|
||||
double score = 0;
|
||||
|
||||
// all the items or v are taken into account
|
||||
|
||||
while(v1_it != v1_end && v2_it != v2_end)
|
||||
{
|
||||
const WordValue& vi = v1_it->second;
|
||||
const WordValue& wi = v2_it->second;
|
||||
|
||||
if(v1_it->first == v2_it->first)
|
||||
{
|
||||
if(vi != 0 && wi != 0) score += vi * log(vi/wi);
|
||||
|
||||
// move v1 and v2 forward
|
||||
++v1_it;
|
||||
++v2_it;
|
||||
}
|
||||
else if(v1_it->first < v2_it->first)
|
||||
{
|
||||
// move v1 forward
|
||||
score += vi * (log(vi) - LOG_EPS);
|
||||
++v1_it;
|
||||
}
|
||||
else
|
||||
{
|
||||
// move v2_it forward, do not add any score
|
||||
v2_it = v2.lower_bound(v1_it->first);
|
||||
// v2_it = (first element >= v1_it.id)
|
||||
}
|
||||
}
|
||||
|
||||
// sum rest of items of v
|
||||
for(; v1_it != v1_end; ++v1_it)
|
||||
if(v1_it->second != 0)
|
||||
score += v1_it->second * (log(v1_it->second) - LOG_EPS);
|
||||
|
||||
return score; // cannot be scaled
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
double BhattacharyyaScoring::score(const BowVector &v1,
|
||||
const BowVector &v2) const
|
||||
{
|
||||
BowVector::const_iterator v1_it, v2_it;
|
||||
const BowVector::const_iterator v1_end = v1.end();
|
||||
const BowVector::const_iterator v2_end = v2.end();
|
||||
|
||||
v1_it = v1.begin();
|
||||
v2_it = v2.begin();
|
||||
|
||||
double score = 0;
|
||||
|
||||
while(v1_it != v1_end && v2_it != v2_end)
|
||||
{
|
||||
const WordValue& vi = v1_it->second;
|
||||
const WordValue& wi = v2_it->second;
|
||||
|
||||
if(v1_it->first == v2_it->first)
|
||||
{
|
||||
score += sqrt(vi * wi);
|
||||
|
||||
// move v1 and v2 forward
|
||||
++v1_it;
|
||||
++v2_it;
|
||||
}
|
||||
else if(v1_it->first < v2_it->first)
|
||||
{
|
||||
// move v1 forward
|
||||
v1_it = v1.lower_bound(v2_it->first);
|
||||
// v1_it = (first element >= v2_it.id)
|
||||
}
|
||||
else
|
||||
{
|
||||
// move v2 forward
|
||||
v2_it = v2.lower_bound(v1_it->first);
|
||||
// v2_it = (first element >= v1_it.id)
|
||||
}
|
||||
}
|
||||
|
||||
return score; // already scaled
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
double DotProductScoring::score(const BowVector &v1,
|
||||
const BowVector &v2) const
|
||||
{
|
||||
BowVector::const_iterator v1_it, v2_it;
|
||||
const BowVector::const_iterator v1_end = v1.end();
|
||||
const BowVector::const_iterator v2_end = v2.end();
|
||||
|
||||
v1_it = v1.begin();
|
||||
v2_it = v2.begin();
|
||||
|
||||
double score = 0;
|
||||
|
||||
while(v1_it != v1_end && v2_it != v2_end)
|
||||
{
|
||||
const WordValue& vi = v1_it->second;
|
||||
const WordValue& wi = v2_it->second;
|
||||
|
||||
if(v1_it->first == v2_it->first)
|
||||
{
|
||||
score += vi * wi;
|
||||
|
||||
// move v1 and v2 forward
|
||||
++v1_it;
|
||||
++v2_it;
|
||||
}
|
||||
else if(v1_it->first < v2_it->first)
|
||||
{
|
||||
// move v1 forward
|
||||
v1_it = v1.lower_bound(v2_it->first);
|
||||
// v1_it = (first element >= v2_it.id)
|
||||
}
|
||||
else
|
||||
{
|
||||
// move v2 forward
|
||||
v2_it = v2.lower_bound(v1_it->first);
|
||||
// v2_it = (first element >= v1_it.id)
|
||||
}
|
||||
}
|
||||
|
||||
return score; // cannot scale
|
||||
}
|
||||
|
||||
// ---------------------------------------------------------------------------
|
||||
// ---------------------------------------------------------------------------
|
||||
|
||||
96
Thirdparty/DBoW2/DBoW2/ScoringObject.h
vendored
Normal file
96
Thirdparty/DBoW2/DBoW2/ScoringObject.h
vendored
Normal file
@@ -0,0 +1,96 @@
|
||||
/**
|
||||
* File: ScoringObject.h
|
||||
* Date: November 2011
|
||||
* Author: Dorian Galvez-Lopez
|
||||
* Description: functions to compute bow scores
|
||||
* License: see the LICENSE.txt file
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __D_T_SCORING_OBJECT__
|
||||
#define __D_T_SCORING_OBJECT__
|
||||
|
||||
#include "BowVector.h"
|
||||
|
||||
namespace DBoW2 {
|
||||
|
||||
/// Base class of scoring functions
|
||||
class GeneralScoring
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Computes the score between two vectors. Vectors must be sorted and
|
||||
* normalized if necessary
|
||||
* @param v (in/out)
|
||||
* @param w (in/out)
|
||||
* @return score
|
||||
*/
|
||||
virtual double score(const BowVector &v, const BowVector &w) const = 0;
|
||||
|
||||
/**
|
||||
* Returns whether a vector must be normalized before scoring according
|
||||
* to the scoring scheme
|
||||
* @param norm norm to use
|
||||
* @return true iff must normalize
|
||||
*/
|
||||
virtual bool mustNormalize(LNorm &norm) const = 0;
|
||||
|
||||
/// Log of epsilon
|
||||
static const double LOG_EPS;
|
||||
// If you change the type of WordValue, make sure you change also the
|
||||
// epsilon value (this is needed by the KL method)
|
||||
|
||||
virtual ~GeneralScoring() {} //!< Required for virtual base classes
|
||||
|
||||
};
|
||||
|
||||
/**
|
||||
* Macro for defining Scoring classes
|
||||
* @param NAME name of class
|
||||
* @param MUSTNORMALIZE if vectors must be normalized to compute the score
|
||||
* @param NORM type of norm to use when MUSTNORMALIZE
|
||||
*/
|
||||
#define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \
|
||||
NAME: public GeneralScoring \
|
||||
{ public: \
|
||||
/** \
|
||||
* Computes score between two vectors \
|
||||
* @param v \
|
||||
* @param w \
|
||||
* @return score between v and w \
|
||||
*/ \
|
||||
virtual double score(const BowVector &v, const BowVector &w) const; \
|
||||
\
|
||||
/** \
|
||||
* Says if a vector must be normalized according to the scoring function \
|
||||
* @param norm (out) if true, norm to use
|
||||
* @return true iff vectors must be normalized \
|
||||
*/ \
|
||||
virtual inline bool mustNormalize(LNorm &norm) const \
|
||||
{ norm = NORM; return MUSTNORMALIZE; } \
|
||||
}
|
||||
|
||||
/// L1 Scoring object
|
||||
class __SCORING_CLASS(L1Scoring, true, L1);
|
||||
|
||||
/// L2 Scoring object
|
||||
class __SCORING_CLASS(L2Scoring, true, L2);
|
||||
|
||||
/// Chi square Scoring object
|
||||
class __SCORING_CLASS(ChiSquareScoring, true, L1);
|
||||
|
||||
/// KL divergence Scoring object
|
||||
class __SCORING_CLASS(KLScoring, true, L1);
|
||||
|
||||
/// Bhattacharyya Scoring object
|
||||
class __SCORING_CLASS(BhattacharyyaScoring, true, L1);
|
||||
|
||||
/// Dot product Scoring object
|
||||
class __SCORING_CLASS(DotProductScoring, false, L1);
|
||||
|
||||
#undef __SCORING_CLASS
|
||||
|
||||
} // namespace DBoW2
|
||||
|
||||
#endif
|
||||
|
||||
1665
Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
vendored
Normal file
1665
Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
vendored
Normal file
File diff suppressed because it is too large
Load Diff
Reference in New Issue
Block a user