Ajout sortie match.txt
This commit is contained in:
parent
d2992f3d26
commit
83e3a70bc1
13 changed files with 107 additions and 23093 deletions
|
@ -1,6 +1,6 @@
|
|||
#include "ASIFT_matcher.hpp"
|
||||
|
||||
ASIFT_matcher::ASIFT_matcher(): _nb_refs(0), _resize_imgs(false), _showDebug(false)
|
||||
ASIFT_matcher::ASIFT_matcher(): _nb_refs(0), _total_num_matchings(0), _resize_imgs(false), _showDebug(false)
|
||||
{
|
||||
default_sift_parameters(_siftParam);
|
||||
}
|
||||
|
@ -127,13 +127,13 @@ bool ASIFT_matcher::addReference(const char* image, unsigned int num_tilts)
|
|||
return true;
|
||||
}
|
||||
|
||||
//Return true if successfull
|
||||
bool ASIFT_matcher::match(const char* image, unsigned int num_tilts)
|
||||
//Return number of match
|
||||
unsigned int ASIFT_matcher::match(const char* image, unsigned int num_tilts)
|
||||
{
|
||||
if(_nb_refs<=0)
|
||||
{
|
||||
cout<<"ASIFT_matcher Error : Trying to match without reference"<<endl;
|
||||
return false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
///// Read input
|
||||
|
@ -229,11 +229,11 @@ bool ASIFT_matcher::match(const char* image, unsigned int num_tilts)
|
|||
cout<<" "<< num_keys <<" ASIFT keypoints found in "<< image << endl;
|
||||
|
||||
//// Match ASIFT keypoints
|
||||
|
||||
int num_matchings = 0;
|
||||
_total_num_matchings=0;
|
||||
|
||||
for(unsigned int i = 0; i<_nb_refs;i++)
|
||||
{
|
||||
int num_matchings = 0;
|
||||
matchingslist matchings;
|
||||
|
||||
cout << "Matching the keypoints..." << endl;
|
||||
|
@ -253,19 +253,20 @@ bool ASIFT_matcher::match(const char* image, unsigned int num_tilts)
|
|||
cout << "Keypoints matching accomplished in " << difftime(tend, tstart) << " seconds." << endl;
|
||||
|
||||
_num_matchings.push_back(num_matchings);
|
||||
_total_num_matchings += num_matchings;
|
||||
_matchings.push_back(matchings);
|
||||
}
|
||||
|
||||
return true;
|
||||
return _total_num_matchings;
|
||||
}
|
||||
|
||||
//Return true if successfull
|
||||
bool ASIFT_matcher::match(vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts)
|
||||
//Return number of match
|
||||
unsigned int ASIFT_matcher::match(vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts)
|
||||
{
|
||||
if(image.size()!=w*h)
|
||||
{
|
||||
cerr<<"Error : Input image size doesn't correspond with parameters"<<endl;
|
||||
return false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
///// Compute ASIFT keypoints
|
||||
|
@ -282,11 +283,11 @@ bool ASIFT_matcher::match(vector<float>& image, unsigned int w, unsigned int h,
|
|||
cout<<" "<< num_keys <<" ASIFT keypoints found in Input image"<< endl;
|
||||
|
||||
//// Match ASIFT keypoints
|
||||
|
||||
int num_matchings = 0;
|
||||
_total_num_matchings=0;
|
||||
|
||||
for(unsigned int i = 0; i<_nb_refs;i++)
|
||||
{
|
||||
int num_matchings = 0;
|
||||
matchingslist matchings;
|
||||
|
||||
cout << "Matching the keypoints..." << endl;
|
||||
|
@ -306,10 +307,11 @@ bool ASIFT_matcher::match(vector<float>& image, unsigned int w, unsigned int h,
|
|||
cout << "Keypoints matching accomplished in " << difftime(tend, tstart) << " seconds." << endl;
|
||||
|
||||
_num_matchings.push_back(num_matchings);
|
||||
_total_num_matchings += num_matchings;
|
||||
_matchings.push_back(matchings);
|
||||
}
|
||||
|
||||
return true;
|
||||
return _total_num_matchings;
|
||||
}
|
||||
|
||||
//Return true if successfull
|
||||
|
@ -495,12 +497,12 @@ void ASIFT_matcher::print() const
|
|||
}
|
||||
}
|
||||
|
||||
unsigned int ASIFT_matcher::getNbMatch() const
|
||||
{
|
||||
unsigned int res = 0;
|
||||
for (unsigned int i=0;i<_num_matchings.size();i++)
|
||||
{
|
||||
res+=_num_matchings[i];
|
||||
}
|
||||
return res;
|
||||
}
|
||||
// unsigned int ASIFT_matcher::getNbMatch() const
|
||||
// {
|
||||
// unsigned int res = 0;
|
||||
// for (unsigned int i=0;i<_num_matchings.size();i++)
|
||||
// {
|
||||
// res+=_num_matchings[i];
|
||||
// }
|
||||
// return res;
|
||||
// }
|
|
@ -38,8 +38,8 @@ public:
|
|||
// virtual ~ASIFT_matcher();
|
||||
|
||||
bool addReference(const char* image, unsigned int num_tilts=1);
|
||||
bool match(const char* image, unsigned int num_tilts =1);
|
||||
bool match(vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts =1);
|
||||
unsigned int match(const char* image, 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 computeCenter(int& cx, int& cy) const;
|
||||
|
@ -51,7 +51,7 @@ public:
|
|||
const vector< pair<int,int> >& getSizeRef() const{ return _size_refs;}
|
||||
const vector<float>& getZoomRef() const{ return _zoom_refs;}
|
||||
const vector < unsigned int >& getNbMatchs() const{ return _num_matchings;}
|
||||
unsigned int getNbMatch() const;
|
||||
unsigned int getNbMatch() const{ return _total_num_matchings;}
|
||||
const vector< matchingslist >& getMatch() const{ return _matchings;}
|
||||
vector< matchingslist >& getMatch(){ return _matchings;}
|
||||
const siftPar& getSiftPar(){ return _siftParam;}
|
||||
|
@ -74,6 +74,7 @@ protected:
|
|||
vector< asift_keypoints > _keys; //Keypoints
|
||||
|
||||
//Matchs
|
||||
unsigned int _total_num_matchings;
|
||||
vector < unsigned int > _num_matchings; //Number of match/reference
|
||||
vector< matchingslist > _matchings; //Matchs
|
||||
|
||||
|
|
Binary file not shown.
|
@ -6,10 +6,6 @@
|
|||
|
||||
#IncludeRegexTransform:
|
||||
|
||||
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/ASIFT_matcher.cpp
|
||||
ASIFT_matcher.hpp
|
||||
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/ASIFT_matcher.hpp
|
||||
|
||||
/home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/ASIFT_matcher.hpp
|
||||
stdio.h
|
||||
-
|
||||
|
|
Binary file not shown.
Binary file not shown.
Before Width: | Height: | Size: 223 KiB |
Binary file not shown.
Before Width: | Height: | Size: 305 KiB |
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
Binary file not shown.
Before Width: | Height: | Size: 184 KiB After Width: | Height: | Size: 184 KiB |
Binary file not shown.
|
@ -17,6 +17,9 @@ int main(int argc, char **argv)
|
|||
return 1;
|
||||
}
|
||||
|
||||
char* output_img = "./results/res.png";
|
||||
char* output_match = "./results/matching.txt";
|
||||
|
||||
//////////////////////////////////////////////// Input
|
||||
float * iarr1;
|
||||
size_t w1, h1;
|
||||
|
@ -108,6 +111,7 @@ int main(int argc, char **argv)
|
|||
"book_training/train_image_001.png"};
|
||||
|
||||
int tilt_ref = 7, tilt_input = 1;
|
||||
int nb_match;
|
||||
|
||||
if(argc>2)
|
||||
{
|
||||
|
@ -123,7 +127,7 @@ int main(int argc, char **argv)
|
|||
|
||||
matcher.addReference(refData[0].c_str(), tilt_ref);
|
||||
matcher.addReference(refData[1].c_str(), tilt_ref);
|
||||
matcher.match(ipixels1_zoom, wS1, hS1, tilt_input);
|
||||
nb_match = matcher.match(ipixels1_zoom, wS1, hS1, tilt_input);
|
||||
|
||||
if(argc>3 && atoi(argv[3])>0)
|
||||
matcher.distFilter(atoi(argv[3]));
|
||||
|
@ -170,9 +174,36 @@ int main(int argc, char **argv)
|
|||
}
|
||||
|
||||
///////////////////////////////////////////////////////////////// Save imgOut
|
||||
write_png_f32("./results/res.png", opixelsASIFT, w1, h1, 1);
|
||||
write_png_f32(output_img, opixelsASIFT, w1, h1, 1);
|
||||
|
||||
delete[] opixelsASIFT; /*memcheck*/
|
||||
|
||||
////// Write the coordinates of the matched points (row1, col1, row2, col2)
|
||||
std::ofstream file(output_match);
|
||||
if (file.is_open())
|
||||
{
|
||||
// Write the number of matchings and number of references in the first line
|
||||
file << nb_match <<" "<<matcher.getNbRef() <<std::endl;
|
||||
|
||||
for(unsigned int i =0; i<matcher.getNbRef();i++)
|
||||
{
|
||||
//Write reference indice before match
|
||||
file<<i<<std::endl;
|
||||
matchingslist matchings = matcher.getMatch()[i];
|
||||
matchingslist::iterator ptr = matchings.begin();
|
||||
for(int i=0; i < (int) matchings.size(); i++, ptr++)
|
||||
{
|
||||
file << zoom1*ptr->first.x << " " << zoom1*ptr->first.y << " " << matcher.getZoomRef()[i]*ptr->second.x <<
|
||||
" " << matcher.getZoomRef()[i]*ptr->second.y << std::endl;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cerr << "Unable to open the file matchings.";
|
||||
}
|
||||
|
||||
file.close();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue