Ajout commentaires/Accesseurs/Nettoyage redondance

This commit is contained in:
Unknown 2018-07-25 16:53:48 +02:00
parent e17412e672
commit d2992f3d26
8 changed files with 47 additions and 30 deletions

View file

@ -1,6 +1,6 @@
#include "ASIFT_matcher.hpp" #include "ASIFT_matcher.hpp"
ASIFT_matcher::ASIFT_matcher(): _showDebug(0), _nb_refs(0), _resize_imgs(false) ASIFT_matcher::ASIFT_matcher(): _nb_refs(0), _resize_imgs(false), _showDebug(false)
{ {
default_sift_parameters(_siftParam); default_sift_parameters(_siftParam);
} }
@ -10,6 +10,7 @@ ASIFT_matcher::ASIFT_matcher(): _showDebug(0), _nb_refs(0), _resize_imgs(false)
// } // }
//Return true if successfull
bool ASIFT_matcher::addReference(const char* image, unsigned int num_tilts) bool ASIFT_matcher::addReference(const char* image, unsigned int num_tilts)
{ {
///// Read input ///// Read input
@ -112,6 +113,7 @@ bool ASIFT_matcher::addReference(const char* image, unsigned int num_tilts)
//Save data //Save data
_im_refs.push_back(ipixels1_zoom); _im_refs.push_back(ipixels1_zoom);
_size_refs.push_back(make_pair(wS1,hS1)); _size_refs.push_back(make_pair(wS1,hS1));
_zoom_refs.push_back(zoom1);
_num_keys.push_back(num_keys); _num_keys.push_back(num_keys);
_num_tilts.push_back(num_tilts); _num_tilts.push_back(num_tilts);
@ -125,6 +127,7 @@ bool ASIFT_matcher::addReference(const char* image, unsigned int num_tilts)
return true; return true;
} }
//Return true if successfull
bool ASIFT_matcher::match(const char* image, unsigned int num_tilts) bool ASIFT_matcher::match(const char* image, unsigned int num_tilts)
{ {
if(_nb_refs<=0) if(_nb_refs<=0)
@ -256,6 +259,7 @@ bool ASIFT_matcher::match(const char* image, unsigned int num_tilts)
return true; return true;
} }
//Return true if successfull
bool ASIFT_matcher::match(vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts) bool ASIFT_matcher::match(vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts)
{ {
if(image.size()!=w*h) if(image.size()!=w*h)
@ -308,6 +312,7 @@ bool ASIFT_matcher::match(vector<float>& image, unsigned int w, unsigned int h,
return true; return true;
} }
//Return true if successfull
bool ASIFT_matcher::computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const bool ASIFT_matcher::computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const
{ {
if(getNbMatch()==0) if(getNbMatch()==0)
@ -351,6 +356,7 @@ bool ASIFT_matcher::computeROI(int& x, int& y, unsigned int& h, unsigned int& w)
return true; return true;
} }
//Return true if successfull
bool ASIFT_matcher::computeCenter(int& cx, int& cy) const bool ASIFT_matcher::computeCenter(int& cx, int& cy) const
{ {
if(getNbMatch()==0) if(getNbMatch()==0)
@ -380,6 +386,7 @@ bool ASIFT_matcher::computeCenter(int& cx, int& cy) const
//Filter keypoint which are far (Euclidian distance) from the center. //Filter keypoint which are far (Euclidian distance) from the center.
//Not optimized //Not optimized
//threshold : 1-68%/2-95%/3-99% //threshold : 1-68%/2-95%/3-99%
//Return true if successfull
bool ASIFT_matcher::distFilter(int threshold=2) bool ASIFT_matcher::distFilter(int threshold=2)
{ {
cout<<"filtering keypoint..."<<endl; cout<<"filtering keypoint..."<<endl;
@ -441,7 +448,7 @@ bool ASIFT_matcher::distFilter(int threshold=2)
{ {
euc_dist =kp_euc_dist[i][j]; euc_dist =kp_euc_dist[i][j];
if(euc_dist<dist_avg+threshold*std_dev) if(euc_dist<dist_avg+threshold*std_dev) //Filtering Condition
{ {
new_match.push_back(_matchings[i][j]); new_match.push_back(_matchings[i][j]);
} }

View file

@ -30,6 +30,7 @@ using namespace std;
typedef vector< vector< keypointslist > > asift_keypoints; typedef vector< vector< keypointslist > > asift_keypoints;
//ASIFT wrapper
class ASIFT_matcher class ASIFT_matcher
{ {
public: public:
@ -44,33 +45,41 @@ public:
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.
void setResizeImg(bool resize_imgs){ _resize_imgs=resize_imgs;}
void showDebug(bool showDebug){ _showDebug=showDebug;} unsigned int getNbRef() const{ return _nb_refs;}
const vector< vector< float > >& getRefImgs() const{ return _im_refs;}
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;} const vector < unsigned int >& getNbMatchs() const{ return _num_matchings;}
unsigned int getNbMatch() const; unsigned int getNbMatch() const;
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;}
void setSiftPar(const siftPar &newSiftPar){ _siftParam = newSiftPar;}
void setResizeImg(bool resize_imgs){ _resize_imgs=resize_imgs;}
void showDebug(bool showDebug){ _showDebug=showDebug;}
protected: protected:
int _showDebug;// = 0;
//Reference Images //Reference Images
// vector< image > _im_refs; // vector< image > _im_refs;
unsigned int _nb_refs;// = 0; unsigned int _nb_refs;// = 0; //Number of reference images
vector< vector< float > > _im_refs; vector< vector< float > > _im_refs; //Reference images used for matching
vector< pair<int,int> > _size_refs; //Width/Height vector< pair<int,int> > _size_refs; //Width/Height
vector<float> _zoom_refs; //Zoom coeffs
//ASIFT Keypoints //ASIFT Keypoints
vector< int > _num_keys; vector< int > _num_keys; //Number of keypoint/reference
vector< int > _num_tilts; //Speed VS Precision vector< int > _num_tilts; //Number of tilts/reference (Speed VS Precision)
vector< asift_keypoints > _keys; vector< asift_keypoints > _keys; //Keypoints
//Matchs //Matchs
vector < unsigned int > _num_matchings; vector < unsigned int > _num_matchings; //Number of match/reference
vector< matchingslist > _matchings; vector< matchingslist > _matchings; //Matchs
siftPar _siftParam; siftPar _siftParam; //SIFT parameters
//Flags //Flags
bool _resize_imgs;// = false; bool _resize_imgs;// = false; //Resize images to IM_X/IM_Y ?
bool _showDebug;// = 0; //Show debugging messages ?
}; };

View file

@ -6,6 +6,10 @@
#IncludeRegexTransform: #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 /home/harle/catkin_ws/src/BaxterInterface/ASIFT_tests/demo_ASIFT_src/ASIFT_matcher.hpp
stdio.h stdio.h
- -

Binary file not shown.

Before

Width:  |  Height:  |  Size: 184 KiB

After

Width:  |  Height:  |  Size: 184 KiB

Before After
Before After

View file

@ -9,7 +9,7 @@ int main(int argc, char **argv)
<< "Usage: " << argv[0] << " imgIn.png [Tilt number option] [Filter option] [Resize option] " << std::endl << "Usage: " << argv[0] << " imgIn.png [Tilt number option] [Filter option] [Resize option] " << std::endl
<< "- imgIn.png: input image (in PNG format). " << std::endl << "- imgIn.png: input image (in PNG format). " << std::endl
<< "- [Tilt number option: 1..(32+ ?)] : 7: Recommended / 1: no tilt. " << std::endl << "- [Tilt number option: 1..(32+ ?)] : 7: Recommended / 1: no tilt. " << std::endl
<< "- [Filter option: 0..3]. Standard deviation filter coeff (1-68%/2-95%/3-99%). 0: no filtering. " << std::endl << "- [Filter option: 0..3]. Standard deviation filter coeff (1-68%/2-95%/3-99%). 0: no filtering (default). " << std::endl
<< "- [Resize option: 0/1]. 1: input images resize to 800x600 (default). 0: no resize. " << std::endl << "- [Resize option: 0/1]. 1: input images resize to 800x600 (default). 0: no resize. " << std::endl
<< " ******************************************************************************* " << std::endl << " ******************************************************************************* " << std::endl
<< " ********************* Jean-Michel Morel, Guoshen Yu, 2010 ******************** " << std::endl << " ********************* Jean-Michel Morel, Guoshen Yu, 2010 ******************** " << std::endl
@ -107,26 +107,23 @@ int main(int argc, char **argv)
"book_training/train_image_000.png", "book_training/train_image_000.png",
"book_training/train_image_001.png"}; "book_training/train_image_001.png"};
int tilt_ref = 7, tilt_input = 1;
if(argc>2)
{
tilt_ref = atoi(argv[2]);
tilt_input = atoi(argv[2]);
}
ASIFT_matcher matcher; ASIFT_matcher matcher;
matcher.setResizeImg(flag_resize); matcher.setResizeImg(flag_resize);
time_t tstart, tend; time_t tstart, tend;
tstart = time(0); tstart = time(0);
// matcher.print(); matcher.addReference(refData[0].c_str(), tilt_ref);
// matcher.match(refData[3].c_str(), 4); matcher.addReference(refData[1].c_str(), tilt_ref);
if(argc>2) matcher.match(ipixels1_zoom, wS1, hS1, tilt_input);
{
matcher.addReference(refData[0].c_str(), atoi(argv[2]));
matcher.addReference(refData[1].c_str(), atoi(argv[2]));
matcher.match(ipixels1_zoom, wS1, hS1, atoi(argv[2]));
}
else
{
matcher.addReference(refData[0].c_str(), 7);
matcher.addReference(refData[1].c_str(), 7);
matcher.match(ipixels1_zoom, wS1, hS1);
}
if(argc>3 && atoi(argv[3])>0) if(argc>3 && atoi(argv[3])>0)
matcher.distFilter(atoi(argv[3])); matcher.distFilter(atoi(argv[3]));