Ajout d'opérateurs au matcher
This commit is contained in:
parent
70dbba6c70
commit
9bed523372
8 changed files with 77 additions and 36 deletions
|
@ -5,6 +5,14 @@ ASIFT_matcher::ASIFT_matcher(): _nb_refs(0), _total_num_matchings(0), _resize_im
|
||||||
default_sift_parameters(_siftParam);
|
default_sift_parameters(_siftParam);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
ASIFT_matcher::ASIFT_matcher(const char* ref_path): ASIFT_matcher()
|
||||||
|
{
|
||||||
|
if(!loadReferences(ref_path))
|
||||||
|
{
|
||||||
|
std::cerr<<"Error : Failed to load references"<<std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// ASIFT_matcher::~ASIFT_matcher()
|
// ASIFT_matcher::~ASIFT_matcher()
|
||||||
// {
|
// {
|
||||||
|
|
||||||
|
@ -607,8 +615,8 @@ bool ASIFT_matcher::loadReferences(const char* ref_path)
|
||||||
std::getline(iss,tmp,' ');
|
std::getline(iss,tmp,' ');
|
||||||
if(VecLength!=atoi(tmp.c_str()))
|
if(VecLength!=atoi(tmp.c_str()))
|
||||||
{
|
{
|
||||||
std::cout<<"Error VecLength doesn't correspond..."<<std::endl;
|
std::cerr<<"Error VecLength doesn't correspond..."<<std::endl;
|
||||||
// return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// std::getline(iss,tmp,' ');
|
// std::getline(iss,tmp,' ');
|
||||||
|
@ -679,6 +687,30 @@ bool ASIFT_matcher::loadReferences(const char* ref_path)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
ASIFT_matcher& ASIFT_matcher::operator=(const ASIFT_matcher& m)
|
||||||
|
{
|
||||||
|
|
||||||
|
_nb_refs=m.getNbRef();
|
||||||
|
_im_refs=m.getRefImgs();
|
||||||
|
_size_refs=m.getSizeRef();
|
||||||
|
_zoom_refs=m.getZoomRef();
|
||||||
|
|
||||||
|
_num_keys=m.getNumKeys();
|
||||||
|
_num_tilts=m.getNumTilts();
|
||||||
|
_keys=m.getKeys();
|
||||||
|
|
||||||
|
_total_num_matchings=m.getNbMatch();
|
||||||
|
_num_matchings=getNbMatchs();
|
||||||
|
_matchings=m.getMatch();
|
||||||
|
|
||||||
|
_siftParam=m.getSiftPar();
|
||||||
|
|
||||||
|
_resize_imgs=m.isResizingImg();
|
||||||
|
_showDebug=m.isShowingDebug();
|
||||||
|
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
//Debugging function
|
//Debugging function
|
||||||
void ASIFT_matcher::print() const
|
void ASIFT_matcher::print() const
|
||||||
{
|
{
|
||||||
|
|
|
@ -32,12 +32,13 @@ class ASIFT_matcher
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
ASIFT_matcher();
|
ASIFT_matcher();
|
||||||
|
ASIFT_matcher(const char* ref_path);
|
||||||
|
ASIFT_matcher(const ASIFT_matcher& matcher) { *this = matcher;}
|
||||||
// virtual ~ASIFT_matcher();
|
// virtual ~ASIFT_matcher();
|
||||||
|
|
||||||
bool addReference(const char* image_path, unsigned int num_tilts=1);
|
bool addReference(const char* image_path, unsigned int num_tilts=1);
|
||||||
unsigned int match(const char* image_path, unsigned int num_tilts =1);
|
unsigned int match(const char* image_path, unsigned int num_tilts =1);
|
||||||
unsigned int match(vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts =1);
|
unsigned int match(vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts =1);
|
||||||
void print() const; //Debugging function
|
|
||||||
bool computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const; //Compute the bounding rectangle of the keypoints
|
bool computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const; //Compute the bounding rectangle of the keypoints
|
||||||
bool computeCenter(int& cx, int& cy) const;
|
bool computeCenter(int& cx, int& cy) const;
|
||||||
bool distFilter(int threshold); //Filter keypoint which are far (Euclidian distance) from the center.
|
bool distFilter(int threshold); //Filter keypoint which are far (Euclidian distance) from the center.
|
||||||
|
@ -45,19 +46,28 @@ public:
|
||||||
bool saveReferences(const char* ref_path) const;
|
bool saveReferences(const char* ref_path) const;
|
||||||
bool loadReferences(const char* ref_path);
|
bool loadReferences(const char* ref_path);
|
||||||
|
|
||||||
|
ASIFT_matcher& operator=(const ASIFT_matcher& m);
|
||||||
|
|
||||||
unsigned int getNbRef() const{ return _nb_refs;}
|
unsigned int getNbRef() const{ return _nb_refs;}
|
||||||
const vector< vector< float > >& getRefImgs() const{ return _im_refs;}
|
const vector< vector< float > >& getRefImgs() const{ return _im_refs;}
|
||||||
const vector< pair<int,int> >& getSizeRef() const{ return _size_refs;}
|
const vector< pair<int,int> >& getSizeRef() const{ return _size_refs;}
|
||||||
const vector<float>& getZoomRef() const{ return _zoom_refs;}
|
const vector<float>& getZoomRef() const{ return _zoom_refs;}
|
||||||
|
const std::vector<int>& getNumKeys() const{ return _num_keys;}
|
||||||
|
const std::vector<int>& getNumTilts() const{ return _num_tilts;}
|
||||||
|
const std::vector< asift_keypoints >& getKeys() const{ return _keys;}
|
||||||
const vector < unsigned int >& getNbMatchs() const{ return _num_matchings;}
|
const vector < unsigned int >& getNbMatchs() const{ return _num_matchings;}
|
||||||
unsigned int getNbMatch() const{ return _total_num_matchings;}
|
unsigned int getNbMatch() const{ return _total_num_matchings;}
|
||||||
const vector< matchingslist >& getMatch() const{ return _matchings;}
|
const vector< matchingslist >& getMatch() const{ return _matchings;}
|
||||||
vector< matchingslist >& getMatch(){ return _matchings;}
|
vector< matchingslist >& getMatch(){ return _matchings;}
|
||||||
const siftPar& getSiftPar(){ return _siftParam;}
|
const siftPar& getSiftPar() const{ return _siftParam;}
|
||||||
void setSiftPar(const siftPar &newSiftPar){ _siftParam = newSiftPar;}
|
void setSiftPar(const siftPar &newSiftPar){ _siftParam = newSiftPar;}
|
||||||
|
bool isResizingImg() const{ return _resize_imgs;}
|
||||||
void setResizeImg(bool resize_imgs){ _resize_imgs=resize_imgs;}
|
void setResizeImg(bool resize_imgs){ _resize_imgs=resize_imgs;}
|
||||||
|
bool isShowingDebug() const{ return _showDebug;}
|
||||||
void showDebug(bool showDebug){ _showDebug=showDebug;}
|
void showDebug(bool showDebug){ _showDebug=showDebug;}
|
||||||
|
|
||||||
|
void print() const; //Debugging function
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
//Reference Images
|
//Reference Images
|
||||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -1,35 +1,34 @@
|
||||||
39 2
|
40 2
|
||||||
0
|
0
|
||||||
362.208 184.382 279.082 122.315
|
291.509 169.803 321.857 265.435
|
||||||
335.039 109.815 103.199 302.382
|
322.192 279.122 521.25 53.2794
|
||||||
368.527 140.516 2.28707e-06 2.7439e-06
|
361.771 216.725 -2.75171e-10 -5.88405e-11
|
||||||
329.485 112.667 5.27024e-39 1.418e-38
|
310.273 236.617 2.06711e-38 5.80946e-39
|
||||||
322.959 119.184 0 0
|
377.929 162.983 0 0
|
||||||
324.178 230.519 0 0
|
|
||||||
355.697 190.284 1.07784e-35 4.42979e-36
|
|
||||||
315.991 235.875 0 0
|
|
||||||
230.152 191.051 2.67878e-35 1.98276e-35
|
|
||||||
223.012 231.746 0 0
|
|
||||||
377.929 162.983 1.15745e-34 7.48296e-35
|
|
||||||
341.004 112.32 0 0
|
|
||||||
322.192 279.122 3.15062e-35 3.2204e-36
|
|
||||||
361.771 216.725 0 0
|
|
||||||
218.599 221.752 2.92356e-34 1.64035e-34
|
|
||||||
261.936 171.287 0 0
|
|
||||||
300.647 157.174 0 0
|
|
||||||
310.273 236.617 0 0
|
|
||||||
363.462 146.017 0 0
|
|
||||||
277.903 162.656 6438.94 5981.52
|
|
||||||
361.959 175.732 42997.8 23137
|
|
||||||
374.229 132.773 0 0
|
|
||||||
221.354 204.377 0 0
|
|
||||||
218.849 212.966 0 0
|
|
||||||
367.28 179.248 0 0
|
|
||||||
291.509 169.803 0 0
|
|
||||||
343.099 119.621 0 0
|
343.099 119.621 0 0
|
||||||
231.499 206.978 9506.8 5965.8
|
329.485 112.667 4.12015e-36 1.10856e-35
|
||||||
371.585 152.449 13102.5 11096.8
|
322.959 119.184 0 0
|
||||||
|
363.462 146.017 1.2775e-32 1.33655e-32
|
||||||
|
230.152 191.051 0 0
|
||||||
|
361.959 175.732 -1.98837e-10 -1.06993e-10
|
||||||
|
223.012 231.746 2.45231e-38 1.21982e-38
|
||||||
|
368.527 140.516 1.11629e-32 1.33926e-32
|
||||||
|
367.28 179.248 0 0
|
||||||
|
355.697 190.284 5.44443e-35 2.23759e-35
|
||||||
|
362.208 184.382 0 0
|
||||||
|
300.647 157.174 0 0
|
||||||
|
324.178 230.519 0 0
|
||||||
|
354.104 176.741 0 0
|
||||||
|
335.039 109.815 2063.98 6047.64
|
||||||
|
317.773 232.706 72922.9 20489.1
|
||||||
|
371.585 152.449 0 0
|
||||||
|
231.499 206.978 0 0
|
||||||
|
315.991 235.875 0 0
|
||||||
|
221.354 204.377 0 0
|
||||||
|
261.936 171.287 0 0
|
||||||
|
277.903 162.656 0 0
|
||||||
|
374.229 132.773 2481.6 3687.22
|
||||||
|
341.004 112.32 7112.49 20058.7
|
||||||
307.57 255.971 1473.99 304.215
|
307.57 255.971 1473.99 304.215
|
||||||
317.773 232.706 0 0
|
322.959 119.184 0 0
|
||||||
294.302 268.305 0 0
|
|
||||||
1
|
1
|
||||||
|
|
Binary file not shown.
Before Width: | Height: | Size: 179 KiB After Width: | Height: | Size: 179 KiB |
Binary file not shown.
|
@ -233,7 +233,7 @@ int main(int argc, char **argv)
|
||||||
{
|
{
|
||||||
cout<<" "<<NbMatch[i]<<endl;
|
cout<<" "<<NbMatch[i]<<endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
int x,y,cx,cy;
|
int x,y,cx,cy;
|
||||||
unsigned int h,w;
|
unsigned int h,w;
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue